diff --git a/.travis.yml b/.travis.yml
index 179beaa8e5..cfaf6580e3 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -13,6 +13,11 @@ script:
tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pyflakes $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda")'
- docker run
tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pylint $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda"); exit $(($? & 3))'
+ - docker run tmppilot /bin/sh -c 'cd /tmp/openpilot/ && make -C cereal && python -m unittest discover common'
+ - docker run tmppilot /bin/sh -c 'cd /tmp/openpilot/ && make -C cereal && python -m unittest discover selfdrive/can'
+ - docker run tmppilot /bin/sh -c 'cd /tmp/openpilot/ && make -C cereal && python -m unittest discover selfdrive/boardd'
+ - docker run tmppilot /bin/sh -c 'cd /tmp/openpilot/ && make -C cereal && python -m unittest discover selfdrive/controls'
+ - docker run tmppilot /bin/sh -c 'cd /tmp/openpilot/ && python -m unittest discover selfdrive/loggerd'
- docker run
-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
index 5305a72237..738679aca5 100644
--- a/CONTRIBUTING.md
+++ b/CONTRIBUTING.md
@@ -10,9 +10,22 @@ Most open source development activity is coordinated through our [Discord](https
* Make sure you have a [GitHub account](https://github.com/signup/free)
* Fork [our repositories](https://github.com/commaai) on GitHub
+## Testing
+
+### Local Testing
+
+You can test your changes on your machine by running `run_docker_tests.sh`. This will run some automated tests in docker against your code.
+
+### Automated Testing
+
+All PRs are automatically checked by travis. Check out `.travis.yml` for what travis runs. Any new tests sould be added to travis.
+
+### Code Style and Linting
+
+Code is automatically check for style by travis as part of the automated tests. You can also run these yourself by running `check_code_quality.sh`.
+
## 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
index 62c655d7c7..f4c667fa03 100644
--- a/Dockerfile.openpilot
+++ b/Dockerfile.openpilot
@@ -2,17 +2,15 @@ FROM ubuntu:16.04
ENV PYTHONUNBUFFERED 1
RUN apt-get update && apt-get install -y \
+ autoconf \
build-essential \
clang \
- vim \
- screen \
wget \
bzip2 \
git \
libglib2.0-0 \
+ libtool \
python-pip \
- capnproto \
- libcapnp-dev \
libzmq5-dev \
libffi-dev \
libusb-1.0-0 \
@@ -21,6 +19,9 @@ RUN apt-get update && apt-get install -y \
ocl-icd-opencl-dev \
opencl-headers
+COPY phonelibs/install_capnp.sh /tmp/install_capnp.sh
+RUN /tmp/install_capnp.sh
+
RUN pip install --upgrade pip==18.0
RUN pip install numpy==1.11.2 scipy==0.18.1 matplotlib==2.1.2
diff --git a/README.md b/README.md
index 3a69dc1c0b..797622c324 100644
--- a/README.md
+++ b/README.md
@@ -92,10 +92,13 @@ Supported Cars
| Kia | Sorento 2018 | All | Yes | Stock | 0mph | 0mph | Custom6|
| Kia | Stinger 2018 | SCC + LKAS | Yes | Stock | 0mph | 0mph | Custom6|
| Lexus | RX Hybrid 2016-19 | All | Yes | Yes2| 0mph | 0mph | Toyota |
+| Subaru | Crosstrek 2018 | EyeSight | Yes | Stock | 0mph | 0mph | Subaru |
| Subaru | Impreza 2019 | EyeSight | Yes | Stock | 0mph | 0mph | Subaru |
+| Toyota | Avalon 2016 | TSS-P | Yes | Yes2| 20mph1| 0mph | Toyota |
| Toyota | Camry 20184 | All | Yes | Stock | 0mph5 | 0mph | Toyota |
| Toyota | C-HR 2017-184 | All | Yes | Stock | 0mph | 0mph | Toyota |
| Toyota | Corolla 2017-18 | All | Yes | Yes2| 20mph1| 0mph | Toyota |
+| Toyota | Corolla Hatchback 2019 | All | Yes | Yes | 0mph | 0mph | Toyota |
| Toyota | Highlander 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
| Toyota | Highlander Hybrid 2018 | All | Yes | Yes2| 0mph | 0mph | Toyota |
| Toyota | Prius 2016 | TSS-P | Yes | Yes2| 0mph | 0mph | Toyota |
@@ -103,6 +106,7 @@ Supported Cars
| Toyota | Prius Prime 2017-19 | All | Yes | Yes2| 0mph | 0mph | Toyota |
| Toyota | Rav4 2016 | TSS-P | Yes | Yes2| 20mph1| 0mph | Toyota |
| Toyota | Rav4 2017-18 | All | Yes | Yes2| 20mph1| 0mph | Toyota |
+| Toyota | Rav4 2019 | All | Yes | Yes | 0mph | 0mph | Toyota |
| Toyota | Rav4 Hybrid 2017-18 | All | Yes | Yes2| 0mph | 0mph | Toyota |
1[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)***
@@ -159,6 +163,7 @@ Directory structure
├── pyextra # Libraries used on EON
└── selfdrive # Code needed to drive the car
├── assets # Fonts and images for UI
+ ├── athena # Allows communication with the app
├── boardd # Daemon to talk to the board
├── can # Helpers for parsing CAN messages
├── car # Car specific code to read states and control actuators
@@ -169,7 +174,6 @@ Directory structure
├── logcatd # Android logcat as a service
├── loggerd # Logger and uploader of car data
├── mapd # Fetches map data and computes next global path
- ├── orbd # Computes ORB features from frames
├── proclogd # Logs information from proc
├── sensord # IMU / GPS interface code
├── test # Car simulator running code through virtual maneuvers
diff --git a/RELEASES.md b/RELEASES.md
index c63b3ef793..3799ad3c68 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,3 +1,17 @@
+Version 0.5.12 (2019-05-16)
+==========================
+ * Improve lateral control for the Prius and Prius Prime
+ * Compress logs before writing to disk
+ * Remove old driving data when storage reaches 90% full
+ * Fix small offset in following distance
+ * Various small CPU optimizations
+ * Improve offroad power consumption: require NEOS Update
+ * Add default speed limits for Estonia thanks to martinl!
+ * Subaru Crosstrek support thanks to martinl!
+ * Toyota Avalon support thanks to njbrown09!
+ * Toyota Rav4 with TSS 2.0 support thansk to wocsor!
+ * Toyota Corolla with TSS 2.0 support thansk to wocsor!
+
Version 0.5.11 (2019-04-17)
========================
* Add support for Subaru
diff --git a/apk/ai.comma.plus.frame.apk b/apk/ai.comma.plus.frame.apk
index 6df4682205..b561d3fd78 100644
Binary files a/apk/ai.comma.plus.frame.apk and b/apk/ai.comma.plus.frame.apk differ
diff --git a/cereal/Makefile b/cereal/Makefile
index dc6b7f9d51..83318bef33 100644
--- a/cereal/Makefile
+++ b/cereal/Makefile
@@ -6,24 +6,24 @@ 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
+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
+
+
ifeq ($(UNAME_M),aarch64)
- CAPNPC=PATH=$(PWD)/../phonelibs/capnp-cpp/aarch64/bin/:$$PATH capnpc
+CAPNPC=PATH=$(PWD)/../phonelibs/capnp-cpp/aarch64/bin/:$$PATH capnpc
else
- CAPNPC=capnpc
+CAPNPC=capnpc
endif
.PHONY: all
diff --git a/cereal/car.capnp b/cereal/car.capnp
index 2915d68713..fe0d84e256 100644
--- a/cereal/car.capnp
+++ b/cereal/car.capnp
@@ -73,6 +73,7 @@ struct CarEvent @0x9b1657f34caf3ad3 {
lowBattery @48;
invalidGiraffeHonda @49;
vehicleModelInvalid @50;
+ controlsFailed @51;
}
}
@@ -281,31 +282,83 @@ struct CarControl {
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);
+ carFingerprint @1 :Text;
+
+ enableGasInterceptor @2 :Bool;
+ enableCruise @3 :Bool;
+ enableCamera @4 :Bool;
+ enableDsu @5 :Bool; # driving support unit
+ enableApgs @6 :Bool; # advanced parking guidance system
+
+ minEnableSpeed @7 :Float32;
+ minSteerSpeed @8 :Float32;
+ safetyModel @9 :Int16;
+ safetyParam @10 :Int16;
+
+ steerMaxBP @11 :List(Float32);
+ steerMaxV @12 :List(Float32);
+ gasMaxBP @13 :List(Float32);
+ gasMaxV @14 :List(Float32);
+ brakeMaxBP @15 :List(Float32);
+ brakeMaxV @16 :List(Float32);
+
+
+ # things about the car in the manual
+ mass @17 :Float32; # [kg] running weight
+ wheelbase @18 :Float32; # [m] distance from rear to front axle
+ centerToFront @19 :Float32; # [m] GC distance to front axle
+ steerRatio @20 :Float32; # [] ratio between front wheels and steering wheel angles
+ steerRatioRear @21 :Float32; # [] rear steering ratio wrt front steering (usually 0)
+
+ # things we can derive
+ rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia
+ tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff
+ tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff
+
+ longitudinalTuning @25 :LongitudinalPIDTuning;
+ lateralTuning :union {
+ pid @26 :LateralPIDTuning;
+ indi @27 :LateralINDITuning;
+ }
+
+ steerLimitAlert @28 :Bool;
+
+ vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state
+ directAccelControl @30 :Bool; # Does the car have direct accel control or just gas/brake
+ stoppingControl @31 :Bool; # Does the car allows full control even at lows speeds when stopping
+ startAccel @32 :Float32; # Required acceleraton to overcome creep braking
+ steerRateCost @33 :Float32; # Lateral MPC cost on steering rate
+ steerControlType @34 :SteerControlType;
+ radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN
+
+ steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds
+ openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control?
+
+ struct LateralPIDTuning {
+ kpBP @0 :List(Float32);
+ kpV @1 :List(Float32);
+ kiBP @2 :List(Float32);
+ kiV @3 :List(Float32);
+ kf @4 :Float32;
+ }
+
+ struct LongitudinalPIDTuning {
+ kpBP @0 :List(Float32);
+ kpV @1 :List(Float32);
+ kiBP @2 :List(Float32);
+ kiV @3 :List(Float32);
+ deadzoneBP @4 :List(Float32);
+ deadzoneV @5 :List(Float32);
+ }
+
+
+ struct LateralINDITuning {
+ outerLoopGain @0 :Float32;
+ innerLoopGain @1 :Float32;
+ timeConstant @2 :Float32;
+ actuatorEffectiveness @3 :Float32;
+ }
+
enum SafetyModels {
# does NOT match board setting
@@ -323,46 +376,6 @@ struct CarParams {
subaru @11;
}
- # 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/log.capnp b/cereal/log.capnp
index 3f79deefe5..84f0a3e809 100644
--- a/cereal/log.capnp
+++ b/cereal/log.capnp
@@ -388,9 +388,9 @@ struct Live100Data {
ufAccelCmd @33 :Float32;
yActualDEPRECATED @6 :Float32;
yDesDEPRECATED @7 :Float32;
- upSteer @8 :Float32;
- uiSteer @9 :Float32;
- ufSteer @34 :Float32;
+ upSteerDEPRECATED @8 :Float32;
+ uiSteerDEPRECATED @9 :Float32;
+ ufSteerDEPRECATED @34 :Float32;
aTargetMinDEPRECATED @10 :Float32;
aTargetMaxDEPRECATED @11 :Float32;
aTarget @35 :Float32;
@@ -428,6 +428,11 @@ struct Live100Data {
vCurvature @46 :Float32;
decelForTurn @47 :Bool;
+ lateralControlState :union {
+ indiState @52 :LateralINDIState;
+ pidState @53 :LateralPIDState;
+ }
+
enum ControlState {
disabled @0;
preEnabled @1;
@@ -455,6 +460,31 @@ struct Live100Data {
full @3; # full screen
}
+ struct LateralINDIState {
+ active @0 :Bool;
+ steerAngle @1 :Float32;
+ steerRate @2 :Float32;
+ steerAccel @3 :Float32;
+ rateSetPoint @4 :Float32;
+ accelSetPoint @5 :Float32;
+ accelError @6 :Float32;
+ delayedOutput @7 :Float32;
+ delta @8 :Float32;
+ output @9 :Float32;
+ }
+
+ struct LateralPIDState {
+ active @0 :Bool;
+ steerAngle @1 :Float32;
+ steerRate @2 :Float32;
+ angleError @3 :Float32;
+ p @4 :Float32;
+ i @5 :Float32;
+ f @6 :Float32;
+ output @7 :Float32;
+ saturated @8 :Bool;
+ }
+
}
struct LiveEventData {
@@ -545,7 +575,7 @@ struct LogRotate {
struct Plan {
mdMonoTime @9 :UInt64;
l20MonoTime @10 :UInt64;
- events @13 :List(Car.CarEvent);
+ eventsDEPRECATED @13 :List(Car.CarEvent);
# lateral, 3rd order polynomial
lateralValidDEPRECATED @0 :Bool;
@@ -583,6 +613,7 @@ struct Plan {
decelForTurn @22 :Bool;
mapValid @25 :Bool;
radarValid @28 :Bool;
+ radarCommIssue @30 :Bool;
processingDelay @29 :Float32;
diff --git a/check_code_quality.sh b/check_code_quality.sh
new file mode 100644
index 0000000000..854d757a84
--- /dev/null
+++ b/check_code_quality.sh
@@ -0,0 +1,11 @@
+#!/bin/bash
+
+pyflakes $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda")
+RESULT=$?
+if [ $RESULT -eq 0 ]; then
+ pylint $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda")
+ RESULT=$? & 3
+fi
+
+[ $RESULT -ne 0 ] && exit 1
+exit 0
diff --git a/common/kalman/Makefile b/common/kalman/Makefile
new file mode 100644
index 0000000000..cb8f092650
--- /dev/null
+++ b/common/kalman/Makefile
@@ -0,0 +1,10 @@
+all: simple_kalman_impl.so
+
+simple_kalman_impl.so: simple_kalman_impl.pyx simple_kalman_impl.pxd simple_kalman_setup.py
+ python simple_kalman_setup.py build_ext --inplace
+ rm -rf build
+ rm simple_kalman_impl.c
+
+.PHONY: clean
+clean:
+ rm -f simple_kalman_impl.so
diff --git a/common/kalman/simple_kalman.py b/common/kalman/simple_kalman.py
index 3f7d049cc5..97b6d792dc 100644
--- a/common/kalman/simple_kalman.py
+++ b/common/kalman/simple_kalman.py
@@ -1,23 +1,10 @@
-import numpy as np
+# pylint: skip-file
+import os
+import subprocess
+kalman_dir = os.path.dirname(os.path.abspath(__file__))
+subprocess.check_call(["make", "simple_kalman_impl.so"], cwd=kalman_dir)
-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
+from simple_kalman_impl import KF1D as KF1D
+# Silence pyflakes
+assert KF1D
diff --git a/common/kalman/simple_kalman_impl.pxd b/common/kalman/simple_kalman_impl.pxd
new file mode 100644
index 0000000000..c81f959272
--- /dev/null
+++ b/common/kalman/simple_kalman_impl.pxd
@@ -0,0 +1,16 @@
+cdef class KF1D:
+ cdef public:
+ double x0_0
+ double x1_0
+ double K0_0
+ double K1_0
+ double A0_0
+ double A0_1
+ double A1_0
+ double A1_1
+ double C0_0
+ double C0_1
+ double A_K_0
+ double A_K_1
+ double A_K_2
+ double A_K_3
\ No newline at end of file
diff --git a/common/kalman/simple_kalman_impl.pyx b/common/kalman/simple_kalman_impl.pyx
new file mode 100644
index 0000000000..43acf7e2a0
--- /dev/null
+++ b/common/kalman/simple_kalman_impl.pyx
@@ -0,0 +1,35 @@
+
+cdef class KF1D:
+ def __init__(self, x0, A, C, K):
+ self.x0_0 = x0[0][0]
+ self.x1_0 = x0[1][0]
+ self.A0_0 = A[0][0]
+ self.A0_1 = A[0][1]
+ self.A1_0 = A[1][0]
+ self.A1_1 = A[1][1]
+ self.C0_0 = C[0]
+ self.C0_1 = C[1]
+ self.K0_0 = K[0][0]
+ self.K1_0 = K[1][0]
+
+ self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0
+ self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1
+ self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0
+ self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1
+
+ def update(self, meas):
+ cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas
+ cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas
+ self.x0_0 = x0_0
+ self.x1_0 = x1_0
+
+ return [self.x0_0, self.x1_0]
+
+ @property
+ def x(self):
+ return [[self.x0_0], [self.x1_0]]
+
+ @x.setter
+ def x(self, x):
+ self.x0_0 = x[0][0]
+ self.x1_0 = x[1][0]
\ No newline at end of file
diff --git a/common/kalman/simple_kalman_old.py b/common/kalman/simple_kalman_old.py
new file mode 100644
index 0000000000..3f7d049cc5
--- /dev/null
+++ b/common/kalman/simple_kalman_old.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/kalman/simple_kalman_setup.py b/common/kalman/simple_kalman_setup.py
new file mode 100644
index 0000000000..bccd9f888f
--- /dev/null
+++ b/common/kalman/simple_kalman_setup.py
@@ -0,0 +1,5 @@
+from distutils.core import setup, Extension
+from Cython.Build import cythonize
+
+setup(name='Simple Kalman Implementation',
+ ext_modules=cythonize(Extension("simple_kalman_impl", ["simple_kalman_impl.pyx"])))
\ No newline at end of file
diff --git a/common/kalman/tests/__init__.py b/common/kalman/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/common/kalman/tests/test_ekf.py b/common/kalman/tests/test_ekf.py
new file mode 100644
index 0000000000..3d6da323d4
--- /dev/null
+++ b/common/kalman/tests/test_ekf.py
@@ -0,0 +1,116 @@
+import numpy as np
+import numpy.matlib
+import unittest
+import timeit
+
+from common.kalman.ekf import EKF, SimpleSensor, FastEKF1D
+
+class TestEKF(EKF):
+ def __init__(self, var_init, Q):
+ super(TestEKF, self).__init__(False)
+ self.identity = numpy.matlib.identity(2)
+ self.state = numpy.matlib.zeros((2, 1))
+ self.covar = self.identity * var_init
+
+ self.process_noise = numpy.matlib.diag(Q)
+
+ def calc_transfer_fun(self, dt):
+ tf = numpy.matlib.identity(2)
+ tf[0, 1] = dt
+ return tf, tf
+
+
+class EKFTest(unittest.TestCase):
+ def test_update_scalar(self):
+ ekf = TestEKF(1e3, [0.1, 1])
+ dt = 1. / 100
+
+ sensor = SimpleSensor(0, 1, 2)
+ readings = map(sensor.read, np.arange(100, 300))
+
+ for reading in readings:
+ ekf.update_scalar(reading)
+ ekf.predict(dt)
+
+ np.testing.assert_allclose(ekf.state, [[300], [100]], 1e-4)
+ np.testing.assert_allclose(
+ ekf.covar,
+ np.asarray([[0.0563, 0.10278], [0.10278, 0.55779]]),
+ atol=1e-4)
+
+ def test_unbiased(self):
+ ekf = TestEKF(1e3, [0., 0.])
+ dt = np.float64(1. / 100)
+
+ sensor = SimpleSensor(0, 1, 2)
+ readings = map(sensor.read, np.arange(1000))
+
+ for reading in readings:
+ ekf.update_scalar(reading)
+ ekf.predict(dt)
+
+ np.testing.assert_allclose(ekf.state, [[1000.], [100.]], 1e-4)
+
+
+class FastEKF1DTest(unittest.TestCase):
+ def test_correctness(self):
+ dt = 1. / 100
+ reading = SimpleSensor(0, 1, 2).read(100)
+
+ ekf = TestEKF(1e3, [0.1, 1])
+ fast_ekf = FastEKF1D(dt, 1e3, [0.1, 1])
+
+ ekf.update_scalar(reading)
+ fast_ekf.update_scalar(reading)
+ self.assertAlmostEqual(ekf.state[0] , fast_ekf.state[0])
+ self.assertAlmostEqual(ekf.state[1] , fast_ekf.state[1])
+ self.assertAlmostEqual(ekf.covar[0, 0], fast_ekf.covar[0])
+ self.assertAlmostEqual(ekf.covar[0, 1], fast_ekf.covar[2])
+ self.assertAlmostEqual(ekf.covar[1, 1], fast_ekf.covar[1])
+
+ ekf.predict(dt)
+ fast_ekf.predict(dt)
+ self.assertAlmostEqual(ekf.state[0] , fast_ekf.state[0])
+ self.assertAlmostEqual(ekf.state[1] , fast_ekf.state[1])
+ self.assertAlmostEqual(ekf.covar[0, 0], fast_ekf.covar[0])
+ self.assertAlmostEqual(ekf.covar[0, 1], fast_ekf.covar[2])
+ self.assertAlmostEqual(ekf.covar[1, 1], fast_ekf.covar[1])
+
+ def test_speed(self):
+ setup = """
+import numpy as np
+from common.kalman.tests.test_ekf import TestEKF
+from common.kalman.ekf import SimpleSensor, FastEKF1D
+
+dt = 1. / 100
+reading = SimpleSensor(0, 1, 2).read(100)
+
+var_init, Q = 1e3, [0.1, 1]
+ekf = TestEKF(var_init, Q)
+fast_ekf = FastEKF1D(dt, var_init, Q)
+ """
+
+ timeit.timeit("""
+ekf.update_scalar(reading)
+ekf.predict(dt)
+ """, setup=setup, number=1000)
+
+ ekf_speed = timeit.timeit("""
+ekf.update_scalar(reading)
+ekf.predict(dt)
+ """, setup=setup, number=20000)
+
+ timeit.timeit("""
+fast_ekf.update_scalar(reading)
+fast_ekf.predict(dt)
+ """, setup=setup, number=1000)
+
+ fast_ekf_speed = timeit.timeit("""
+fast_ekf.update_scalar(reading)
+fast_ekf.predict(dt)
+ """, setup=setup, number=20000)
+
+ assert fast_ekf_speed < ekf_speed / 4
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/common/kalman/tests/test_simple_kalman.py b/common/kalman/tests/test_simple_kalman.py
new file mode 100644
index 0000000000..c1f9f7b03c
--- /dev/null
+++ b/common/kalman/tests/test_simple_kalman.py
@@ -0,0 +1,85 @@
+import unittest
+import random
+import timeit
+import numpy as np
+
+from common.kalman.simple_kalman import KF1D
+from common.kalman.simple_kalman_old import KF1D as KF1D_old
+
+
+class TestSimpleKalman(unittest.TestCase):
+ def setUp(self):
+ dt = 0.01
+ x0_0 = 0.0
+ x1_0 = 0.0
+ A0_0 = 1.0
+ A0_1 = dt
+ A1_0 = 0.0
+ A1_1 = 1.0
+ C0_0 = 1.0
+ C0_1 = 0.0
+ K0_0 = 0.12287673
+ K1_0 = 0.29666309
+
+ self.kf_old = KF1D_old(x0=np.matrix([[x0_0], [x1_0]]),
+ A=np.matrix([[A0_0, A0_1], [A1_0, A1_1]]),
+ C=np.matrix([C0_0, C0_1]),
+ K=np.matrix([[K0_0], [K1_0]]))
+
+ self.kf = KF1D(x0=[[x0_0], [x1_0]],
+ A=[[A0_0, A0_1], [A1_0, A1_1]],
+ C=[C0_0, C0_1],
+ K=[[K0_0], [K1_0]])
+
+ def test_getter_setter(self):
+ self.kf.x = [[1.0], [1.0]]
+ self.assertEqual(self.kf.x, [[1.0], [1.0]])
+
+ def update_returns_state(self):
+ x = self.kf.update(100)
+ self.assertEqual(x, self.kf.x)
+
+ def test_old_equal_new(self):
+ for _ in range(1000):
+ v_wheel = random.uniform(0, 200)
+
+ x_old = self.kf_old.update(v_wheel)
+ x = self.kf.update(v_wheel)
+
+ # Compare the output x, verify that the error is less than 1e-4
+ self.assertAlmostEqual(x_old[0], x[0])
+ self.assertAlmostEqual(x_old[1], x[1])
+
+
+ def test_new_is_faster(self):
+ setup = """
+import numpy as np
+
+from common.kalman.simple_kalman import KF1D
+from common.kalman.simple_kalman_old import KF1D as KF1D_old
+
+dt = 0.01
+x0_0 = 0.0
+x1_0 = 0.0
+A0_0 = 1.0
+A0_1 = dt
+A1_0 = 0.0
+A1_1 = 1.0
+C0_0 = 1.0
+C0_1 = 0.0
+K0_0 = 0.12287673
+K1_0 = 0.29666309
+
+kf_old = KF1D_old(x0=np.matrix([[x0_0], [x1_0]]),
+ A=np.matrix([[A0_0, A0_1], [A1_0, A1_1]]),
+ C=np.matrix([C0_0, C0_1]),
+ K=np.matrix([[K0_0], [K1_0]]))
+
+kf = KF1D(x0=[[x0_0], [x1_0]],
+ A=[[A0_0, A0_1], [A1_0, A1_1]],
+ C=[C0_0, C0_1],
+ K=[[K0_0], [K1_0]])
+ """
+ kf_speed = timeit.timeit("kf.update(1234)", setup=setup, number=10000)
+ kf_old_speed = timeit.timeit("kf_old.update(1234)", setup=setup, number=10000)
+ self.assertTrue(kf_speed < kf_old_speed / 4)
diff --git a/common/timeout.py b/common/timeout.py
new file mode 100644
index 0000000000..c2c1f69712
--- /dev/null
+++ b/common/timeout.py
@@ -0,0 +1,28 @@
+import signal
+
+class TimeoutException(Exception):
+ pass
+
+class Timeout:
+ """
+ Timeout context manager.
+ For example this code will raise a TimeoutException:
+ with Timeout(seconds=5, error_msg="Sleep was too long"):
+ time.sleep(10)
+ """
+ def __init__(self, seconds, error_msg=None):
+ if error_msg is None:
+ error_msg = 'Timed out after {} seconds'.format(seconds)
+ self.seconds = seconds
+ self.error_msg = error_msg
+
+ def handle_timeout(self, signume, frame):
+ raise TimeoutException(self.error_msg)
+
+ def __enter__(self):
+ signal.signal(signal.SIGALRM, self.handle_timeout)
+ signal.alarm(self.seconds)
+
+ def __exit__(self, exc_type, exc_val, exc_tb):
+ signal.alarm(0)
+
diff --git a/common/transformations/camera.py b/common/transformations/camera.py
index 78c9df9890..1ac9bc5b28 100644
--- a/common/transformations/camera.py
+++ b/common/transformations/camera.py
@@ -200,3 +200,14 @@ def transform_img(base_img,
augmented_rgb[:cyy] = cv2.warpPerspective(base_img, M, (output_size[0], cyy), borderMode=cv2.BORDER_REPLICATE)
return augmented_rgb
+
+def yuv_crop(frame, output_size, center=None):
+ # output_size in camera coordinates so u,v
+ # center in array coordinates so row, column
+ rgb = cv2.cvtColor(frame, cv2.COLOR_YUV2RGB_I420)
+ if not center:
+ center = (rgb.shape[0]/2, rgb.shape[1]/2)
+ rgb_crop = rgb[center[0] - output_size[1]/2: center[0] + output_size[1]/2,
+ center[1] - output_size[0]/2: center[1] + output_size[0]/2]
+ return cv2.cvtColor(rgb_crop, cv2.COLOR_RGB2YUV_I420)
+
diff --git a/common/transformations/model.py b/common/transformations/model.py
index afb4d66716..e832cb7ee9 100644
--- a/common/transformations/model.py
+++ b/common/transformations/model.py
@@ -1,8 +1,7 @@
import numpy as np
from common.transformations.camera import eon_focal_length, \
- vp_from_ke, \
- get_view_frame_from_road_frame, \
+ vp_from_ke, get_view_frame_from_road_frame, \
FULL_FRAME_SIZE
# segnet
@@ -117,6 +116,16 @@ def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height=model
return np.dot(camera_from_model_camera, model_camera_from_model_frame)
+def get_camera_frame_from_medmodel_frame(camera_frame_from_road_frame):
+ camera_frame_from_ground = camera_frame_from_road_frame[:, (0, 1, 3)]
+ medmodel_frame_from_ground = medmodel_frame_from_road_frame[:, (0, 1, 3)]
+
+ ground_from_medmodel_frame = np.linalg.inv(medmodel_frame_from_ground)
+ camera_frame_from_medmodel_frame = np.dot(camera_frame_from_ground, ground_from_medmodel_frame)
+
+ return camera_frame_from_medmodel_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)]
diff --git a/phonelibs/bzip2/build.txt b/phonelibs/bzip2/build.txt
new file mode 100644
index 0000000000..ceb3226210
--- /dev/null
+++ b/phonelibs/bzip2/build.txt
@@ -0,0 +1,6 @@
+git clone https://github.com/enthought/bzip2-1.0.6.git
+cd bzip2-1.0.6
+git reset --hard 288acf97a15d558f96c24c89f578b724d6e06b0c
+
+make libbz2.a
+cp libbz2.a ../
diff --git a/phonelibs/bzip2/bzlib.h b/phonelibs/bzip2/bzlib.h
new file mode 100644
index 0000000000..8277123da8
--- /dev/null
+++ b/phonelibs/bzip2/bzlib.h
@@ -0,0 +1,282 @@
+
+/*-------------------------------------------------------------*/
+/*--- Public header file for the library. ---*/
+/*--- bzlib.h ---*/
+/*-------------------------------------------------------------*/
+
+/* ------------------------------------------------------------------
+ This file is part of bzip2/libbzip2, a program and library for
+ lossless, block-sorting data compression.
+
+ bzip2/libbzip2 version 1.0.6 of 6 September 2010
+ Copyright (C) 1996-2010 Julian Seward
+
+ Please read the WARNING, DISCLAIMER and PATENTS sections in the
+ README file.
+
+ This program is released under the terms of the license contained
+ in the file LICENSE.
+ ------------------------------------------------------------------ */
+
+
+#ifndef _BZLIB_H
+#define _BZLIB_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define BZ_RUN 0
+#define BZ_FLUSH 1
+#define BZ_FINISH 2
+
+#define BZ_OK 0
+#define BZ_RUN_OK 1
+#define BZ_FLUSH_OK 2
+#define BZ_FINISH_OK 3
+#define BZ_STREAM_END 4
+#define BZ_SEQUENCE_ERROR (-1)
+#define BZ_PARAM_ERROR (-2)
+#define BZ_MEM_ERROR (-3)
+#define BZ_DATA_ERROR (-4)
+#define BZ_DATA_ERROR_MAGIC (-5)
+#define BZ_IO_ERROR (-6)
+#define BZ_UNEXPECTED_EOF (-7)
+#define BZ_OUTBUFF_FULL (-8)
+#define BZ_CONFIG_ERROR (-9)
+
+typedef
+ struct {
+ char *next_in;
+ unsigned int avail_in;
+ unsigned int total_in_lo32;
+ unsigned int total_in_hi32;
+
+ char *next_out;
+ unsigned int avail_out;
+ unsigned int total_out_lo32;
+ unsigned int total_out_hi32;
+
+ void *state;
+
+ void *(*bzalloc)(void *,int,int);
+ void (*bzfree)(void *,void *);
+ void *opaque;
+ }
+ bz_stream;
+
+
+#ifndef BZ_IMPORT
+#define BZ_EXPORT
+#endif
+
+#ifndef BZ_NO_STDIO
+/* Need a definitition for FILE */
+#include
+#endif
+
+#ifdef _WIN32
+# include
+# ifdef small
+ /* windows.h define small to char */
+# undef small
+# endif
+# ifdef BZ_EXPORT
+# define BZ_API(func) WINAPI func
+# define BZ_EXTERN extern
+# else
+ /* import windows dll dynamically */
+# define BZ_API(func) (WINAPI * func)
+# define BZ_EXTERN
+# endif
+#else
+# define BZ_API(func) func
+# define BZ_EXTERN extern
+#endif
+
+
+/*-- Core (low-level) library functions --*/
+
+BZ_EXTERN int BZ_API(BZ2_bzCompressInit) (
+ bz_stream* strm,
+ int blockSize100k,
+ int verbosity,
+ int workFactor
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzCompress) (
+ bz_stream* strm,
+ int action
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzCompressEnd) (
+ bz_stream* strm
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzDecompressInit) (
+ bz_stream *strm,
+ int verbosity,
+ int small
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzDecompress) (
+ bz_stream* strm
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzDecompressEnd) (
+ bz_stream *strm
+ );
+
+
+
+/*-- High(er) level library functions --*/
+
+#ifndef BZ_NO_STDIO
+#define BZ_MAX_UNUSED 5000
+
+typedef void BZFILE;
+
+BZ_EXTERN BZFILE* BZ_API(BZ2_bzReadOpen) (
+ int* bzerror,
+ FILE* f,
+ int verbosity,
+ int small,
+ void* unused,
+ int nUnused
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzReadClose) (
+ int* bzerror,
+ BZFILE* b
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzReadGetUnused) (
+ int* bzerror,
+ BZFILE* b,
+ void** unused,
+ int* nUnused
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzRead) (
+ int* bzerror,
+ BZFILE* b,
+ void* buf,
+ int len
+ );
+
+BZ_EXTERN BZFILE* BZ_API(BZ2_bzWriteOpen) (
+ int* bzerror,
+ FILE* f,
+ int blockSize100k,
+ int verbosity,
+ int workFactor
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzWrite) (
+ int* bzerror,
+ BZFILE* b,
+ void* buf,
+ int len
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzWriteClose) (
+ int* bzerror,
+ BZFILE* b,
+ int abandon,
+ unsigned int* nbytes_in,
+ unsigned int* nbytes_out
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzWriteClose64) (
+ int* bzerror,
+ BZFILE* b,
+ int abandon,
+ unsigned int* nbytes_in_lo32,
+ unsigned int* nbytes_in_hi32,
+ unsigned int* nbytes_out_lo32,
+ unsigned int* nbytes_out_hi32
+ );
+#endif
+
+
+/*-- Utility functions --*/
+
+BZ_EXTERN int BZ_API(BZ2_bzBuffToBuffCompress) (
+ char* dest,
+ unsigned int* destLen,
+ char* source,
+ unsigned int sourceLen,
+ int blockSize100k,
+ int verbosity,
+ int workFactor
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzBuffToBuffDecompress) (
+ char* dest,
+ unsigned int* destLen,
+ char* source,
+ unsigned int sourceLen,
+ int small,
+ int verbosity
+ );
+
+
+/*--
+ Code contributed by Yoshioka Tsuneo (tsuneo@rr.iij4u.or.jp)
+ to support better zlib compatibility.
+ This code is not _officially_ part of libbzip2 (yet);
+ I haven't tested it, documented it, or considered the
+ threading-safeness of it.
+ If this code breaks, please contact both Yoshioka and me.
+--*/
+
+BZ_EXTERN const char * BZ_API(BZ2_bzlibVersion) (
+ void
+ );
+
+#ifndef BZ_NO_STDIO
+BZ_EXTERN BZFILE * BZ_API(BZ2_bzopen) (
+ const char *path,
+ const char *mode
+ );
+
+BZ_EXTERN BZFILE * BZ_API(BZ2_bzdopen) (
+ int fd,
+ const char *mode
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzread) (
+ BZFILE* b,
+ void* buf,
+ int len
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzwrite) (
+ BZFILE* b,
+ void* buf,
+ int len
+ );
+
+BZ_EXTERN int BZ_API(BZ2_bzflush) (
+ BZFILE* b
+ );
+
+BZ_EXTERN void BZ_API(BZ2_bzclose) (
+ BZFILE* b
+ );
+
+BZ_EXTERN const char * BZ_API(BZ2_bzerror) (
+ BZFILE *b,
+ int *errnum
+ );
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
+/*-------------------------------------------------------------*/
+/*--- end bzlib.h ---*/
+/*-------------------------------------------------------------*/
diff --git a/phonelibs/bzip2/libbz2.a b/phonelibs/bzip2/libbz2.a
new file mode 100644
index 0000000000..0efccceb17
Binary files /dev/null and b/phonelibs/bzip2/libbz2.a differ
diff --git a/phonelibs/install_capnp.sh b/phonelibs/install_capnp.sh
new file mode 100755
index 0000000000..b83e1ffda1
--- /dev/null
+++ b/phonelibs/install_capnp.sh
@@ -0,0 +1,39 @@
+set -e
+echo "Installing capnp"
+
+cd /tmp
+VERSION=0.6.1
+wget https://capnproto.org/capnproto-c++-${VERSION}.tar.gz
+tar xvf capnproto-c++-${VERSION}.tar.gz
+cd capnproto-c++-${VERSION}
+CXXFLAGS="-fPIC" ./configure
+
+make -j4
+
+# manually build binaries statically
+g++ -std=gnu++11 -I./src -I./src -DKJ_HEADER_WARNINGS -DCAPNP_HEADER_WARNINGS -DCAPNP_INCLUDE_DIR=\"/usr/local/include\" -pthread -O2 -DNDEBUG -pthread -pthread -o .libs/capnp src/capnp/compiler/module-loader.o src/capnp/compiler/capnp.o ./.libs/libcapnpc.a ./.libs/libcapnp.a ./.libs/libkj.a -lpthread -pthread
+
+g++ -std=gnu++11 -I./src -I./src -DKJ_HEADER_WARNINGS -DCAPNP_HEADER_WARNINGS -DCAPNP_INCLUDE_DIR=\"/usr/local/include\" -pthread -O2 -DNDEBUG -pthread -pthread -o .libs/capnpc-c++ src/capnp/compiler/capnpc-c++.o ./.libs/libcapnp.a ./.libs/libkj.a -lpthread -pthread
+
+g++ -std=gnu++11 -I./src -I./src -DKJ_HEADER_WARNINGS -DCAPNP_HEADER_WARNINGS -DCAPNP_INCLUDE_DIR=\"/usr/local/include\" -pthread -O2 -DNDEBUG -pthread -pthread -o .libs/capnpc-capnp src/capnp/compiler/capnpc-capnp.o ./.libs/libcapnp.a ./.libs/libkj.a -lpthread -pthread
+
+cp .libs/capnp /usr/local/bin/
+ln -s /usr/local/bin/capnp /usr/local/bin/capnpc
+cp .libs/capnpc-c++ /usr/local/bin/
+cp .libs/capnpc-capnp /usr/local/bin/
+cp .libs/*.a /usr/local/lib
+
+cd /tmp
+echo "Installing c-capnp"
+git clone https://github.com/commaai/c-capnproto.git
+cd c-capnproto
+git submodule update --init --recursive
+autoreconf -f -i -s
+CXXFLAGS="-fPIC" ./configure
+make -j4
+
+# manually build binaries statically
+gcc -fPIC -o .libs/capnpc-c compiler/capnpc-c.o compiler/schema.capnp.o compiler/str.o ./.libs/libcapnp_c.a
+
+cp .libs/capnpc-c /usr/local/bin/
+cp .libs/*.a /usr/local/lib
diff --git a/phonelibs/zmq/x64/include/czmq.h b/phonelibs/zmq/x64/include/czmq.h
new file mode 100644
index 0000000000..dbf1fe5e40
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/czmq_library.h b/phonelibs/zmq/x64/include/czmq_library.h
new file mode 100644
index 0000000000..89dc4eb917
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/czmq_prelude.h b/phonelibs/zmq/x64/include/czmq_prelude.h
new file mode 100644
index 0000000000..534f47023c
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zactor.h b/phonelibs/zmq/x64/include/zactor.h
new file mode 100644
index 0000000000..c865c65daf
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zarmour.h b/phonelibs/zmq/x64/include/zarmour.h
new file mode 100644
index 0000000000..c7f299f7af
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zauth.h b/phonelibs/zmq/x64/include/zauth.h
new file mode 100644
index 0000000000..3e0e59ecab
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zbeacon.h b/phonelibs/zmq/x64/include/zbeacon.h
new file mode 100644
index 0000000000..78917e9577
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zcert.h b/phonelibs/zmq/x64/include/zcert.h
new file mode 100644
index 0000000000..3161bc0596
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zcertstore.h b/phonelibs/zmq/x64/include/zcertstore.h
new file mode 100644
index 0000000000..689b228ac1
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zchunk.h b/phonelibs/zmq/x64/include/zchunk.h
new file mode 100644
index 0000000000..56f29b161a
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zclock.h b/phonelibs/zmq/x64/include/zclock.h
new file mode 100644
index 0000000000..eb064162c4
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zconfig.h b/phonelibs/zmq/x64/include/zconfig.h
new file mode 100644
index 0000000000..df0c708493
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zdigest.h b/phonelibs/zmq/x64/include/zdigest.h
new file mode 100644
index 0000000000..def9e86053
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zdir.h b/phonelibs/zmq/x64/include/zdir.h
new file mode 100644
index 0000000000..6c5551b57e
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zdir_patch.h b/phonelibs/zmq/x64/include/zdir_patch.h
new file mode 100644
index 0000000000..8d15b9aeb4
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zfile.h b/phonelibs/zmq/x64/include/zfile.h
new file mode 100644
index 0000000000..75c35774b9
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zframe.h b/phonelibs/zmq/x64/include/zframe.h
new file mode 100644
index 0000000000..728093c36c
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zgossip.h b/phonelibs/zmq/x64/include/zgossip.h
new file mode 100644
index 0000000000..647cb28c08
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zhash.h b/phonelibs/zmq/x64/include/zhash.h
new file mode 100644
index 0000000000..138adf63ac
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zhashx.h b/phonelibs/zmq/x64/include/zhashx.h
new file mode 100644
index 0000000000..360a773ee8
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/ziflist.h b/phonelibs/zmq/x64/include/ziflist.h
new file mode 100644
index 0000000000..cb2b144802
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zlist.h b/phonelibs/zmq/x64/include/zlist.h
new file mode 100644
index 0000000000..1dcd39b995
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zlistx.h b/phonelibs/zmq/x64/include/zlistx.h
new file mode 100644
index 0000000000..512637cef3
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zloop.h b/phonelibs/zmq/x64/include/zloop.h
new file mode 100644
index 0000000000..83f46f282a
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zmonitor.h b/phonelibs/zmq/x64/include/zmonitor.h
new file mode 100644
index 0000000000..b490bcb1a0
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zmq.h b/phonelibs/zmq/x64/include/zmq.h
new file mode 100644
index 0000000000..21a78eb657
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zmq_utils.h b/phonelibs/zmq/x64/include/zmq_utils.h
new file mode 100644
index 0000000000..f29638d553
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zmsg.h b/phonelibs/zmq/x64/include/zmsg.h
new file mode 100644
index 0000000000..d8a84d1f41
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zpoller.h b/phonelibs/zmq/x64/include/zpoller.h
new file mode 100644
index 0000000000..3b394c3516
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zproc.h b/phonelibs/zmq/x64/include/zproc.h
new file mode 100644
index 0000000000..4fd3fcf445
--- /dev/null
+++ b/phonelibs/zmq/x64/include/zproc.h
@@ -0,0 +1,168 @@
+/* =========================================================================
+ 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, ...) 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
+// @end
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/phonelibs/zmq/x64/include/zproxy.h b/phonelibs/zmq/x64/include/zproxy.h
new file mode 100644
index 0000000000..f672c5e724
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zrex.h b/phonelibs/zmq/x64/include/zrex.h
new file mode 100644
index 0000000000..8b50618a34
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zsock.h b/phonelibs/zmq/x64/include/zsock.h
new file mode 100644
index 0000000000..9ab060d6a3
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zstr.h b/phonelibs/zmq/x64/include/zstr.h
new file mode 100644
index 0000000000..67f2f852b6
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zsys.h b/phonelibs/zmq/x64/include/zsys.h
new file mode 100644
index 0000000000..200271d924
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/ztimerset.h b/phonelibs/zmq/x64/include/ztimerset.h
new file mode 100644
index 0000000000..29633fafdb
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/ztrie.h b/phonelibs/zmq/x64/include/ztrie.h
new file mode 100644
index 0000000000..6fd53234b1
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/include/zuuid.h b/phonelibs/zmq/x64/include/zuuid.h
new file mode 100644
index 0000000000..afc1104fea
--- /dev/null
+++ b/phonelibs/zmq/x64/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/x64/lib/libczmq.a b/phonelibs/zmq/x64/lib/libczmq.a
new file mode 100644
index 0000000000..9045eb980e
Binary files /dev/null and b/phonelibs/zmq/x64/lib/libczmq.a differ
diff --git a/phonelibs/zmq/x64/lib/libczmq.la b/phonelibs/zmq/x64/lib/libczmq.la
new file mode 100755
index 0000000000..8e4a9ee364
--- /dev/null
+++ b/phonelibs/zmq/x64/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/batman/one/external/zmq/lib -L/usr/local/lib /home/batman/one/external/zmq/lib/libzmq.la -lrt -lpthread -ldl'
+
+# 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/batman/one/external/zmq/lib'
diff --git a/phonelibs/zmq/x64/lib/libczmq.so b/phonelibs/zmq/x64/lib/libczmq.so
new file mode 120000
index 0000000000..db9aa60f9b
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libczmq.so
@@ -0,0 +1 @@
+libczmq.so.4.0.2
\ No newline at end of file
diff --git a/phonelibs/zmq/x64/lib/libczmq.so.4 b/phonelibs/zmq/x64/lib/libczmq.so.4
new file mode 120000
index 0000000000..db9aa60f9b
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libczmq.so.4
@@ -0,0 +1 @@
+libczmq.so.4.0.2
\ No newline at end of file
diff --git a/phonelibs/zmq/x64/lib/libczmq.so.4.0.2 b/phonelibs/zmq/x64/lib/libczmq.so.4.0.2
new file mode 100755
index 0000000000..eaf4cce8b9
Binary files /dev/null and b/phonelibs/zmq/x64/lib/libczmq.so.4.0.2 differ
diff --git a/phonelibs/zmq/x64/lib/libzmq.a b/phonelibs/zmq/x64/lib/libzmq.a
new file mode 100644
index 0000000000..28c77cc36e
Binary files /dev/null and b/phonelibs/zmq/x64/lib/libzmq.a differ
diff --git a/phonelibs/zmq/x64/lib/libzmq.la b/phonelibs/zmq/x64/lib/libzmq.la
new file mode 100644
index 0000000000..69652b3463
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libzmq.la
@@ -0,0 +1,41 @@
+# libzmq.la - a libtool library file
+# Generated by libtool (GNU libtool) 2.4.6 Debian-2.4.6-0.1
+#
+# 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 cannot 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/batman/one/external/zmq/lib'
diff --git a/phonelibs/zmq/x64/lib/libzmq.lai b/phonelibs/zmq/x64/lib/libzmq.lai
new file mode 100644
index 0000000000..93c1a83dc3
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libzmq.lai
@@ -0,0 +1,41 @@
+# libzmq.la - a libtool library file
+# Generated by libtool (GNU libtool) 2.4.6 Debian-2.4.6-0.1
+#
+# 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 cannot 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='/usr/local/lib'
diff --git a/phonelibs/zmq/x64/lib/libzmq.so b/phonelibs/zmq/x64/lib/libzmq.so
new file mode 120000
index 0000000000..ef44cafc6a
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libzmq.so
@@ -0,0 +1 @@
+libzmq.so.5.1.2
\ No newline at end of file
diff --git a/phonelibs/zmq/x64/lib/libzmq.so.5 b/phonelibs/zmq/x64/lib/libzmq.so.5
new file mode 120000
index 0000000000..ef44cafc6a
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/libzmq.so.5
@@ -0,0 +1 @@
+libzmq.so.5.1.2
\ No newline at end of file
diff --git a/phonelibs/zmq/x64/lib/libzmq.so.5.1.2 b/phonelibs/zmq/x64/lib/libzmq.so.5.1.2
new file mode 100755
index 0000000000..e08e8c2dfb
Binary files /dev/null and b/phonelibs/zmq/x64/lib/libzmq.so.5.1.2 differ
diff --git a/phonelibs/zmq/x64/lib/pkgconfig/libczmq.pc b/phonelibs/zmq/x64/lib/pkgconfig/libczmq.pc
new file mode 100644
index 0000000000..b6fb3dc133
--- /dev/null
+++ b/phonelibs/zmq/x64/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/batman/one/external/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: -L/usr/local/lib -lzmq
+
+################################################################################
+# 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/x64/lib/pkgconfig/libzmq.pc b/phonelibs/zmq/x64/lib/pkgconfig/libzmq.pc
new file mode 100644
index 0000000000..aba3d3a75e
--- /dev/null
+++ b/phonelibs/zmq/x64/lib/pkgconfig/libzmq.pc
@@ -0,0 +1,10 @@
+prefix=/home/batman/one/external/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
+Cflags: -I${includedir}
diff --git a/run_docker_tests.sh b/run_docker_tests.sh
index a153aac73b..dc629e6137 100755
--- a/run_docker_tests.sh
+++ b/run_docker_tests.sh
@@ -3,6 +3,12 @@ set -e
docker build -t tmppilot -f Dockerfile.openpilot .
+docker run --rm \
+ tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py'
+docker run --rm \
+ tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pyflakes $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda")'
+docker run --rm \
+ tmppilot /bin/sh -c 'cd /tmp/openpilot/ && pylint $(find . -iname "*.py" | grep -vi "^\./pyextra.*" | grep -vi "^\./panda"); exit $(($? & 3))'
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/athena/athenad.py b/selfdrive/athena/athenad.py
index 501806969c..2671672c52 100755
--- a/selfdrive/athena/athenad.py
+++ b/selfdrive/athena/athenad.py
@@ -6,9 +6,11 @@ import time
import threading
import traceback
import zmq
+import requests
import six.moves.queue
from jsonrpc import JSONRPCResponseManager, dispatcher
from websocket import create_connection, WebSocketTimeoutException
+from selfdrive.loggerd.config import ROOT
import selfdrive.crash as crash
import selfdrive.messaging as messaging
@@ -71,6 +73,19 @@ def getMessage(service=None, timeout=1000):
ret = messaging.recv_one(socket)
return ret.to_dict()
+@dispatcher.add_method
+def listDataDirectory():
+ files = [os.path.relpath(os.path.join(dp, f), ROOT) for dp, dn, fn in os.walk(ROOT) for f in fn]
+ return files
+
+@dispatcher.add_method
+def uploadFileToUrl(fn, url, headers):
+ if len(fn) == 0 or fn[0] == '/' or '..' in fn:
+ return 500
+ with open(os.path.join(ROOT, fn), "rb") as f:
+ ret = requests.put(url, data=f, headers=headers, timeout=10)
+ return ret.status_code
+
def ws_recv(ws, end_event):
while not end_event.is_set():
try:
diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile
index 893edde545..7dfbb225c0 100644
--- a/selfdrive/boardd/Makefile
+++ b/selfdrive/boardd/Makefile
@@ -46,6 +46,7 @@ all: boardd
include ../common/cereal.mk
OBJS = boardd.o \
+ can_list_to_can_capnp.o \
../common/swaglog.o \
../common/params.o \
../common/util.o \
@@ -72,6 +73,15 @@ boardd.o: boardd.cc
-I../../ \
-c -o '$@' '$<'
+
+boardd_api_impl.so: libcan_list_to_can_capnp.a boardd_api_impl.pyx boardd_setup.py
+ python boardd_setup.py build_ext --inplace
+ rm -rf build
+ rm -f boardd_api_impl.cpp
+
+libcan_list_to_can_capnp.a: can_list_to_can_capnp.o $(CEREAL_OBJS)
+ ar rcs '$@' $^
+
%.o: %.c
@echo "[ CC ] $@"
$(CC) $(CFLAGS) -MMD \
@@ -81,8 +91,16 @@ boardd.o: boardd.cc
$(JSON_FLAGS) \
-c -o '$@' '$<'
+%.o: %.cc
+ @echo "[ CC ] $@"
+ $(CXX) $(CXXFLAGS) -MMD \
+ -Iinclude -I.. -I../.. \
+ $(CEREAL_CXXFLAGS) \
+ $(ZMQ_FLAGS) \
+ -c -o '$@' '$<'
+
.PHONY: clean
clean:
- rm -f boardd $(OBJS) $(DEPS)
+ rm -f boardd libcan_list_to_can_capnp.a boardd_api_impl.so $(OBJS) $(DEPS)
-include $(DEPS)
diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc
index dd89d4d6d4..3b293307ab 100644
--- a/selfdrive/boardd/boardd.cc
+++ b/selfdrive/boardd/boardd.cc
@@ -85,6 +85,7 @@ void *safety_setter_thread(void *s) {
// 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);
+ free(value);
capnp::FlatArrayMessageReader cmsg(amsg);
cereal::CarParams::Reader car_params = cmsg.getRoot();
diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py
old mode 100755
new mode 100644
index 2ebd2e9ffa..d3bcb14710
--- a/selfdrive/boardd/boardd.py
+++ b/selfdrive/boardd/boardd.py
@@ -1,49 +1,13 @@
-#!/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
-
+# pylint: skip-file
import os
-import struct
-import zmq
-import time
+import subprocess
-import selfdrive.messaging as messaging
-from common.realtime import Ratekeeper
-from selfdrive.services import service_list
-from selfdrive.swaglog import cloudlog
+# Cython
+boardd_api_dir = os.path.dirname(os.path.abspath(__file__))
+subprocess.check_call(["make", "boardd_api_impl.so"], cwd=boardd_api_dir)
+from selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp
+assert can_list_to_can_capnp
-# 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 = []
@@ -51,199 +15,3 @@ def can_capnp_to_can_list(can, src_filter=None):
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 = [can_capnp_to_can_list(x.can) for x in tsc]
- snds = [x for x in snds if x[-1] <= 1]
- can_send_many(snds)
-
- # recv @ 100hz
- can_msgs = can_recv()
- print("sent %d got %d" % (len(snds), 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: {0} {1}".format(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: {0} {1}".format(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/boardd/boardd_api_impl.pyx b/selfdrive/boardd/boardd_api_impl.pyx
new file mode 100644
index 0000000000..75aa1081c3
--- /dev/null
+++ b/selfdrive/boardd/boardd_api_impl.pyx
@@ -0,0 +1,25 @@
+# distutils: language = c++
+from libcpp.vector cimport vector
+from libcpp.string cimport string
+from libcpp cimport bool
+
+cdef struct can_frame:
+ long address
+ string dat
+ long busTime
+ long src
+
+cdef extern void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan)
+
+def can_list_to_can_capnp(can_msgs, msgtype='can'):
+ cdef vector[can_frame] can_list
+ cdef can_frame f
+ for can_msg in can_msgs:
+ f.address = can_msg[0]
+ f.busTime = can_msg[1]
+ f.dat = can_msg[2]
+ f.src = can_msg[3]
+ can_list.push_back(f)
+ cdef string out
+ can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan')
+ return out
diff --git a/selfdrive/boardd/boardd_setup.py b/selfdrive/boardd/boardd_setup.py
new file mode 100644
index 0000000000..f614a06161
--- /dev/null
+++ b/selfdrive/boardd/boardd_setup.py
@@ -0,0 +1,25 @@
+import subprocess
+from distutils.core import setup, Extension
+from Cython.Build import cythonize
+
+PHONELIBS = '../../phonelibs'
+
+ARCH = subprocess.check_output(["uname", "-m"]).rstrip()
+ARCH_DIR = 'x64' if ARCH == "x86_64" else 'aarch64'
+
+setup(name='Boardd API Implementation',
+ ext_modules=cythonize(
+ Extension(
+ "boardd_api_impl",
+ libraries=[':libcan_list_to_can_capnp.a', ':libcapnp.a', ':libcapnp.a', ':libkj.a'],
+ library_dirs=[
+ './',
+ PHONELIBS + '/capnp-cpp/' + ARCH_DIR + '/lib/',
+ PHONELIBS + '/capnp-c/' + ARCH_DIR + '/lib/'
+ ],
+ sources=['boardd_api_impl.pyx'],
+ language="c++",
+ extra_compile_args=["-std=c++11"],
+ )
+ )
+)
diff --git a/selfdrive/boardd/can_list_to_can_capnp.cc b/selfdrive/boardd/can_list_to_can_capnp.cc
new file mode 100644
index 0000000000..626c1e2a98
--- /dev/null
+++ b/selfdrive/boardd/can_list_to_can_capnp.cc
@@ -0,0 +1,36 @@
+#include
+#include
+#include
+#include "common/timing.h"
+#include
+#include "cereal/gen/cpp/log.capnp.h"
+#include "cereal/gen/cpp/car.capnp.h"
+
+typedef struct {
+ long address;
+ std::string dat;
+ long busTime;
+ long src;
+} can_frame;
+
+extern "C" {
+
+void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendCan) {
+ capnp::MallocMessageBuilder msg;
+ cereal::Event::Builder event = msg.initRoot();
+ event.setLogMonoTime(nanos_since_boot());
+
+ auto canData = sendCan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size());
+ int i = 0;
+ for (auto it = can_list.begin(); it != can_list.end(); it++, i++) {
+ canData[i].setAddress(it->address);
+ canData[i].setBusTime(it->busTime);
+ canData[i].setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size()));
+ canData[i].setSrc(it->src);
+ }
+ auto words = capnp::messageToFlatArray(msg);
+ auto bytes = words.asBytes();
+ out.append((const char *)bytes.begin(), bytes.size());
+}
+
+}
diff --git a/selfdrive/boardd/tests/__init__.py b/selfdrive/boardd/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py
new file mode 100755
index 0000000000..9ce5f7f3e1
--- /dev/null
+++ b/selfdrive/boardd/tests/boardd_old.py
@@ -0,0 +1,247 @@
+#!/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
+from selfdrive.boardd.boardd import can_capnp_to_can_list
+
+# 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
+
+
+# *** 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)&0xFF))
+ 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, msgtype='sendcan')
+ 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).to_bytes()
+ logcan.send(dat)
+
+ # 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: {0} {1}".format(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)
+
+ # 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: {0} {1}".format(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/boardd/tests/fuzzer.py b/selfdrive/boardd/tests/fuzzer.py
new file mode 100755
index 0000000000..cb6edf7106
--- /dev/null
+++ b/selfdrive/boardd/tests/fuzzer.py
@@ -0,0 +1,19 @@
+#!/usr/bin/env python
+import time
+import random
+
+from boardd_old import can_init, can_recv, can_send_many, can_health
+
+if __name__ == "__main__":
+ can_init()
+ while 1:
+ c = random.randint(0, 3)
+ if c == 0:
+ print can_recv()
+ elif c == 1:
+ print can_health()
+ elif c == 2:
+ many = [[0x123, 0, "abcdef", 0]] * random.randint(1, 10)
+ can_send_many(many)
+ elif c == 3:
+ time.sleep(random.randint(0, 100) / 1000.0)
diff --git a/selfdrive/boardd/tests/test_boardd_api.py b/selfdrive/boardd/tests/test_boardd_api.py
new file mode 100644
index 0000000000..0e862b0952
--- /dev/null
+++ b/selfdrive/boardd/tests/test_boardd_api.py
@@ -0,0 +1,76 @@
+import random
+import numpy as np
+
+import boardd_old
+import selfdrive.boardd.boardd as boardd
+
+from common.realtime import sec_since_boot
+from cereal import log
+import unittest
+
+
+def generate_random_can_data_list():
+ can_list = []
+ cnt = random.randint(1, 64)
+ for j in xrange(cnt):
+ can_data = np.random.bytes(random.randint(1, 8))
+ can_list.append([random.randint(0, 128), random.randint(0, 128), can_data, random.randint(0, 128)])
+ return can_list, cnt
+
+
+class TestBoarddApiMethods(unittest.TestCase):
+ def test_correctness(self):
+ for i in xrange(1000):
+ can_list, _ = generate_random_can_data_list()
+
+ # Sendcan
+ # Old API
+ m_old = boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes()
+ # new API
+ m = boardd.can_list_to_can_capnp(can_list, 'sendcan')
+
+ ev_old = log.Event.from_bytes(m_old)
+ ev = log.Event.from_bytes(m)
+ self.assertEqual(ev_old.which(), ev.which())
+ self.assertEqual(len(ev.sendcan), len(ev_old.sendcan))
+ for i in xrange(len(ev.sendcan)):
+ attrs = ['address', 'busTime', 'dat', 'src']
+ for attr in attrs:
+ self.assertEqual(getattr(ev.sendcan[i], attr, 'new'), getattr(ev_old.sendcan[i], attr, 'old'))
+
+ # Can
+ m_old = boardd_old.can_list_to_can_capnp(can_list, 'can').to_bytes()
+ # new API
+ m = boardd.can_list_to_can_capnp(can_list, 'can')
+
+ ev_old = log.Event.from_bytes(m_old)
+ ev = log.Event.from_bytes(m)
+ self.assertEqual(ev_old.which(), ev.which())
+ self.assertEqual(len(ev.can), len(ev_old.can))
+ for i in xrange(len(ev.can)):
+ attrs = ['address', 'busTime', 'dat', 'src']
+ for attr in attrs:
+ self.assertEqual(getattr(ev.can[i], attr, 'new'), getattr(ev_old.can[i], attr, 'old'))
+
+ def test_performance(self):
+ can_list, cnt = generate_random_can_data_list()
+ recursions = 1000
+
+ n1 = sec_since_boot()
+ for i in xrange(recursions):
+ boardd_old.can_list_to_can_capnp(can_list, 'sendcan').to_bytes()
+ n2 = sec_since_boot()
+ elapsed_old = n2 - n1
+
+ # print('Old API, elapsed time: {} secs'.format(elapsed_old))
+ n1 = sec_since_boot()
+ for i in xrange(recursions):
+ boardd.can_list_to_can_capnp(can_list)
+ n2 = sec_since_boot()
+ elapsed_new = n2 - n1
+ # print('New API, elapsed time: {} secs'.format(elapsed_new))
+ self.assertTrue(elapsed_new < elapsed_old / 2)
+
+
+if __name__ == '__main__':
+ unittest.main()
diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py
new file mode 100755
index 0000000000..1b6f1b1387
--- /dev/null
+++ b/selfdrive/boardd/tests/test_boardd_loopback.py
@@ -0,0 +1,51 @@
+#!/usr/bin/env python
+"""Run boardd with the BOARDD_LOOPBACK envvar before running this test."""
+
+import os
+import random
+import zmq
+import time
+
+from selfdrive.boardd.boardd import can_list_to_can_capnp
+from selfdrive.messaging import drain_sock, pub_sock, sub_sock
+from selfdrive.services import service_list
+
+def get_test_string():
+ return b"test"+os.urandom(10)
+
+BUS = 0
+
+def main():
+ context = zmq.Context()
+
+ rcv = sub_sock(context, service_list['can'].port) # port 8006
+ snd = pub_sock(context, service_list['sendcan'].port) # port 8017
+ time.sleep(0.3) # wait to bind before send/recv
+
+ for i in range(10):
+ print("Loop %d" % i)
+ at = random.randint(1024, 2000)
+ st = get_test_string()[0:8]
+ snd.send(can_list_to_can_capnp([[at, 0, st, 0]], msgtype='sendcan').to_bytes())
+ time.sleep(0.1)
+ res = drain_sock(rcv, True)
+ assert len(res) == 1
+
+ res = res[0].can
+ assert len(res) == 2
+
+ msg0, msg1 = res
+
+ assert msg0.dat == st
+ assert msg1.dat == st
+
+ assert msg0.address == at
+ assert msg1.address == at
+
+ assert msg0.src == 0x80 | BUS
+ assert msg1.src == BUS
+
+ print("Success")
+
+if __name__ == "__main__":
+ main()
diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile
index 1909a7bb93..918c445288 100644
--- a/selfdrive/can/Makefile
+++ b/selfdrive/can/Makefile
@@ -23,9 +23,8 @@ ifeq ($(UNAME_S),Darwin)
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
+ ZMQ_FLAGS = -I$(PHONELIBS)/zmq/x64/include
+ ZMQ_LIBS = -L$(PHONELIBS)/zmq/x64/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
@@ -67,6 +66,11 @@ libdbc.so:: $(LIBDBC_OBJS) $(DBC_OBJS)
$(CEREAL_CXXFLAGS) \
$(CEREAL_LIBS)
+packer_impl.so: packer_impl.pyx packer_setup.py
+ python packer_setup.py build_ext --inplace
+ rm -rf build
+ rm -f packer_impl.cpp
+
$(OBJDIR)/%.o: %.cc
@echo "[ CXX ] $@"
$(CXX) -fPIC -c -o '$@' $^ \
diff --git a/selfdrive/can/packer.cc b/selfdrive/can/packer.cc
index 17171f1550..d0e8419788 100644
--- a/selfdrive/can/packer.cc
+++ b/selfdrive/can/packer.cc
@@ -129,4 +129,8 @@ extern "C" {
return cp->pack(address, std::vector(vals, vals+num_vals), counter);
}
+ uint64_t canpack_pack_vector(void* inst, uint32_t address, const std::vector &signals, int counter) {
+ CANPacker *cp = (CANPacker*)inst;
+ return cp->pack(address, signals, counter);
+ }
}
diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py
index 7f3c8d2858..81a8c34270 100644
--- a/selfdrive/can/packer.py
+++ b/selfdrive/can/packer.py
@@ -1,68 +1,9 @@
-import six
-import struct
-from selfdrive.can.libdbc_py import libdbc, ffi
+# pylint: skip-file
+import os
+import subprocess
+can_dir = os.path.dirname(os.path.abspath(__file__))
+subprocess.check_call(["make", "packer_impl.so"], cwd=can_dir)
-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 six.iteritems(values):
- 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"))
+from selfdrive.can.packer_impl import CANPacker
+assert CANPacker
diff --git a/selfdrive/can/packer_impl.pyx b/selfdrive/can/packer_impl.pyx
new file mode 100644
index 0000000000..26ce8c1267
--- /dev/null
+++ b/selfdrive/can/packer_impl.pyx
@@ -0,0 +1,111 @@
+# distutils: language = c++
+from libc.stdint cimport uint32_t, uint64_t
+from libcpp.vector cimport vector
+from libcpp.map cimport map
+from libcpp.string cimport string
+from libcpp cimport bool
+from posix.dlfcn cimport dlopen, dlsym, RTLD_LAZY
+import os
+import subprocess
+
+cdef struct SignalPackValue:
+ const char* name
+ double value
+
+ctypedef enum SignalType:
+ DEFAULT,
+ HONDA_CHECKSUM,
+ HONDA_COUNTER,
+ TOYOTA_CHECKSUM,
+ PEDAL_CHECKSUM,
+ PEDAL_COUNTER
+
+cdef struct Signal:
+ const char* name
+ int b1, b2, bo
+ bool is_signed
+ double factor, offset
+ SignalType type
+
+
+
+cdef struct Msg:
+ const char* name
+ uint32_t address
+ unsigned int size
+ size_t num_sigs
+ const Signal *sigs
+
+cdef struct Val:
+ const char* name
+ uint32_t address
+ const char* def_val
+ const Signal *sigs
+
+cdef struct DBC:
+ const char* name
+ size_t num_msgs
+ const Msg *msgs
+ const Val *vals
+ size_t num_vals
+
+ctypedef void * (*canpack_init_func)(const char* dbc_name)
+ctypedef uint64_t (*canpack_pack_vector_func)(void* inst, uint32_t address, const vector[SignalPackValue] &signals, int counter)
+ctypedef const DBC * (*dbc_lookup_func)(const char* dbc_name)
+
+
+cdef class CANPacker(object):
+ cdef void *packer
+ cdef const DBC *dbc
+ cdef map[string, (int, int)] name_to_address_and_size
+ cdef map[int, int] address_to_size
+ cdef canpack_init_func canpack_init
+ cdef canpack_pack_vector_func canpack_pack_vector
+ cdef dbc_lookup_func dbc_lookup
+
+ def __init__(self, dbc_name):
+ 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)
+ cdef void *libdbc = dlopen(libdbc_fn, RTLD_LAZY)
+ self.canpack_init = dlsym(libdbc, 'canpack_init')
+ self.canpack_pack_vector = dlsym(libdbc, 'canpack_pack_vector')
+ self.dbc_lookup = dlsym(libdbc, 'dbc_lookup')
+ self.packer = self.canpack_init(dbc_name)
+ self.dbc = self.dbc_lookup(dbc_name)
+ num_msgs = self.dbc[0].num_msgs
+ for i in range(num_msgs):
+ msg = self.dbc[0].msgs[i]
+ self.name_to_address_and_size[string(msg.name)] = (msg.address, msg.size)
+ self.address_to_size[msg.address] = msg.size
+
+ cdef uint64_t pack(self, addr, values, counter):
+ cdef vector[SignalPackValue] values_thing
+ cdef SignalPackValue spv
+ for name, value in values.iteritems():
+ spv.name = name
+ spv.value = value
+ values_thing.push_back(spv)
+
+ return self.canpack_pack_vector(self.packer, addr, values_thing, counter)
+
+ cdef inline uint64_t ReverseBytes(self, 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))
+
+ cpdef make_can_msg(self, name_or_addr, bus, values, counter=-1):
+ cdef int addr, size
+ if type(name_or_addr) == int:
+ addr = name_or_addr
+ size = self.address_to_size[name_or_addr]
+ else:
+ addr, size = self.name_to_address_and_size[name_or_addr]
+ cdef uint64_t val = self.pack(addr, values, counter)
+ val = self.ReverseBytes(val)
+ return [addr, 0, (&val)[:size], bus]
diff --git a/selfdrive/can/packer_setup.py b/selfdrive/can/packer_setup.py
new file mode 100644
index 0000000000..a36d4199ee
--- /dev/null
+++ b/selfdrive/can/packer_setup.py
@@ -0,0 +1,5 @@
+from distutils.core import setup, Extension
+from Cython.Build import cythonize
+
+setup(name='CAN Packer API Implementation',
+ ext_modules=cythonize(Extension("packer_impl", ["packer_impl.pyx"], language="c++", extra_compile_args=["-std=c++11"])))
diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py
index 83d0f66237..2e8384f637 100644
--- a/selfdrive/can/parser.py
+++ b/selfdrive/can/parser.py
@@ -1,4 +1,3 @@
-import six
import time
from collections import defaultdict
import numbers
@@ -59,7 +58,7 @@ class CANParser(object):
{
'address': msg_address,
'check_frequency': freq,
- } for msg_address, freq in six.iteritems(message_options)])
+ } for msg_address, freq in message_options.items()])
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)
diff --git a/selfdrive/can/process_dbc.py b/selfdrive/can/process_dbc.py
index 31b1315968..3f3f2ddcad 100755
--- a/selfdrive/can/process_dbc.py
+++ b/selfdrive/can/process_dbc.py
@@ -2,7 +2,7 @@
import os
import glob
import sys
-import six
+
import jinja2
from collections import Counter
@@ -39,10 +39,10 @@ def main():
continue #skip output is newer than template and dbc
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(six.iteritems(can_dbc.msgs)) if msg_sigs]
+ for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.items()) 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(six.iteritems(def_vals))]
+ def_vals = [(address, sig) for address, sig in sorted(def_vals.items())]
if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"):
checksum_type = "honda"
diff --git a/selfdrive/can/tests/__init__.py b/selfdrive/can/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/selfdrive/can/tests/packer_old.py b/selfdrive/can/tests/packer_old.py
new file mode 100644
index 0000000000..0c17c2e4d9
--- /dev/null
+++ b/selfdrive/can/tests/packer_old.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/tests/test_packer_chrysler.py b/selfdrive/can/tests/test_packer_chrysler.py
new file mode 100644
index 0000000000..da85a98415
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_chrysler.py
@@ -0,0 +1,35 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+import selfdrive.car.chrysler.chryslercan as chryslercan
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.chrysler_cp_old = CANPackerOld("chrysler_pacifica_2017_hybrid")
+ self.chrysler_cp = CANPacker("chrysler_pacifica_2017_hybrid")
+
+ def test_correctness(self):
+ # Test all commands, randomize the params.
+ for _ in xrange(1000):
+ gear = ('drive', 'reverse', 'low')[random.randint(0, 3) % 3]
+ lkas_active = (random.randint(0, 2) % 2 == 0)
+ hud_alert = random.randint(0, 6)
+ hud_count = random.randint(0, 65536)
+ lkas_car_model = random.randint(0, 65536)
+ m_old = chryslercan.create_lkas_hud(self.chrysler_cp_old, gear, lkas_active, hud_alert, hud_count, lkas_car_model)
+ m = chryslercan.create_lkas_hud(self.chrysler_cp, gear, lkas_active, hud_alert, hud_count, lkas_car_model)
+ self.assertEqual(m_old, m)
+
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ moving_fast = (random.randint(0, 2) % 2 == 0)
+ frame = random.randint(0, 65536)
+ m_old = chryslercan.create_lkas_command(self.chrysler_cp_old, apply_steer, moving_fast, frame)
+ m = chryslercan.create_lkas_command(self.chrysler_cp, apply_steer, moving_fast, frame)
+ self.assertEqual(m_old, m)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/can/tests/test_packer_gm.py b/selfdrive/can/tests/test_packer_gm.py
new file mode 100644
index 0000000000..db5631fbbe
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_gm.py
@@ -0,0 +1,66 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+import selfdrive.car.gm.gmcan as gmcan
+from selfdrive.car.gm.interface import CanBus as GMCanBus
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.gm_cp_old = CANPackerOld("gm_global_a_powertrain")
+ self.gm_cp = CANPacker("gm_global_a_powertrain")
+
+ self.ct6_cp_old = CANPackerOld("cadillac_ct6_chassis")
+ self.ct6_cp = CANPacker("cadillac_ct6_chassis")
+
+ def test_correctness(self):
+ # Test all cars' commands, randomize the params.
+ for _ in xrange(1000):
+ bus = random.randint(0, 65536)
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ idx = random.randint(0, 65536)
+ lkas_active = (random.randint(0, 2) % 2 == 0)
+ m_old = gmcan.create_steering_control(self.gm_cp_old, bus, apply_steer, idx, lkas_active)
+ m = gmcan.create_steering_control(self.gm_cp, bus, apply_steer, idx, lkas_active)
+ self.assertEqual(m_old, m)
+
+ canbus = GMCanBus()
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ v_ego = random.randint(0, 65536)
+ idx = random.randint(0, 65536)
+ enabled = (random.randint(0, 2) % 2 == 0)
+ m_old = gmcan.create_steering_control_ct6(self.ct6_cp_old, canbus, apply_steer, v_ego, idx, enabled)
+ m = gmcan.create_steering_control_ct6(self.ct6_cp, canbus, apply_steer, v_ego, idx, enabled)
+ self.assertEqual(m_old, m)
+
+ bus = random.randint(0, 65536)
+ throttle = random.randint(0, 65536)
+ idx = random.randint(0, 65536)
+ acc_engaged = (random.randint(0, 2) % 2 == 0)
+ at_full_stop = (random.randint(0, 2) % 2 == 0)
+ m_old = gmcan.create_gas_regen_command(self.gm_cp_old, bus, throttle, idx, acc_engaged, at_full_stop)
+ m = gmcan.create_gas_regen_command(self.gm_cp, bus, throttle, idx, acc_engaged, at_full_stop)
+ self.assertEqual(m_old, m)
+
+ bus = random.randint(0, 65536)
+ apply_brake = (random.randint(0, 2) % 2 == 0)
+ idx = random.randint(0, 65536)
+ near_stop = (random.randint(0, 2) % 2 == 0)
+ at_full_stop = (random.randint(0, 2) % 2 == 0)
+ m_old = gmcan.create_friction_brake_command(self.ct6_cp_old, bus, apply_brake, idx, near_stop, at_full_stop)
+ m = gmcan.create_friction_brake_command(self.ct6_cp, bus, apply_brake, idx, near_stop, at_full_stop)
+ self.assertEqual(m_old, m)
+
+ bus = random.randint(0, 65536)
+ acc_engaged = (random.randint(0, 2) % 2 == 0)
+ target_speed_kph = random.randint(0, 65536)
+ lead_car_in_sight = (random.randint(0, 2) % 2 == 0)
+ m_old = gmcan.create_acc_dashboard_command(self.gm_cp_old, bus, acc_engaged, target_speed_kph, lead_car_in_sight)
+ m = gmcan.create_acc_dashboard_command(self.gm_cp, bus, acc_engaged, target_speed_kph, lead_car_in_sight)
+ self.assertEqual(m_old, m)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/can/tests/test_packer_honda.py b/selfdrive/can/tests/test_packer_honda.py
new file mode 100644
index 0000000000..58b841f5a2
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_honda.py
@@ -0,0 +1,56 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+import selfdrive.car.honda.hondacan as hondacan
+from selfdrive.car.honda.values import HONDA_BOSCH
+from selfdrive.car.honda.carcontroller import HUDData
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.honda_cp_old = CANPackerOld("honda_pilot_touring_2017_can_generated")
+ self.honda_cp = CANPacker("honda_pilot_touring_2017_can_generated")
+
+ def test_correctness(self):
+ # Test all commands, randomize the params.
+ for _ in xrange(1000):
+ apply_brake = (random.randint(0, 2) % 2 == 0)
+ pump_on = (random.randint(0, 2) % 2 == 0)
+ pcm_override = (random.randint(0, 2) % 2 == 0)
+ pcm_cancel_cmd = (random.randint(0, 2) % 2 == 0)
+ chime = random.randint(0, 65536)
+ fcw = random.randint(0, 65536)
+ idx = random.randint(0, 65536)
+ m_old = hondacan.create_brake_command(self.honda_cp_old, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, chime, fcw, idx)
+ m = hondacan.create_brake_command(self.honda_cp, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, chime, fcw, idx)
+ self.assertEqual(m_old, m)
+
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ lkas_active = (random.randint(0, 2) % 2 == 0)
+ car_fingerprint = HONDA_BOSCH[0]
+ idx = random.randint(0, 65536)
+ m_old = hondacan.create_steering_control(self.honda_cp_old, apply_steer, lkas_active, car_fingerprint, idx)
+ m = hondacan.create_steering_control(self.honda_cp, apply_steer, lkas_active, car_fingerprint, idx)
+ self.assertEqual(m_old, m)
+
+ pcm_speed = random.randint(0, 65536)
+ hud = HUDData(random.randint(0, 65536), random.randint(0, 65536), 1, random.randint(0, 65536),
+ 0xc1, random.randint(0, 65536), random.randint(0, 65536), random.randint(0, 65536),
+ random.randint(0, 65536), random.randint(0, 65536), random.randint(0, 65536))
+ car_fingerprint = HONDA_BOSCH[0]
+ idx = random.randint(0, 65536)
+ m_old = hondacan.create_ui_commands(self.honda_cp_old, pcm_speed, hud, car_fingerprint, idx)
+ m = hondacan.create_ui_commands(self.honda_cp, pcm_speed, hud, car_fingerprint, idx)
+ self.assertEqual(m_old, m)
+
+ button_val = random.randint(0, 65536)
+ idx = random.randint(0, 65536)
+ m_old = hondacan.spam_buttons_command(self.honda_cp_old, button_val, idx)
+ m = hondacan.spam_buttons_command(self.honda_cp, button_val, idx)
+ self.assertEqual(m_old, m)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/can/tests/test_packer_hyundai.py b/selfdrive/can/tests/test_packer_hyundai.py
new file mode 100644
index 0000000000..d9e829ad59
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_hyundai.py
@@ -0,0 +1,70 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+import selfdrive.car.hyundai.hyundaican as hyundaican
+from selfdrive.car.hyundai.values import CHECKSUM as hyundai_checksum
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.hyundai_cp_old = CANPackerOld("hyundai_kia_generic")
+ self.hyundai_cp = CANPacker("hyundai_kia_generic")
+
+ def test_correctness(self):
+ # Test all commands, randomize the params.
+ for _ in xrange(1000):
+ # Hyundai
+ car_fingerprint = hyundai_checksum["crc8"][0]
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ steer_req = (random.randint(0, 2) % 2 == 0)
+ cnt = random.randint(0, 65536)
+ enabled = (random.randint(0, 2) % 2 == 0)
+ lkas11 = {
+ "CF_Lkas_LdwsSysState": random.randint(0,65536),
+ "CF_Lkas_SysWarning": random.randint(0,65536),
+ "CF_Lkas_LdwsLHWarning": random.randint(0,65536),
+ "CF_Lkas_LdwsRHWarning": random.randint(0,65536),
+ "CF_Lkas_HbaLamp": random.randint(0,65536),
+ "CF_Lkas_FcwBasReq": random.randint(0,65536),
+ "CF_Lkas_ToiFlt": random.randint(0,65536),
+ "CF_Lkas_HbaSysState": random.randint(0,65536),
+ "CF_Lkas_FcwOpt": random.randint(0,65536),
+ "CF_Lkas_HbaOpt": random.randint(0,65536),
+ "CF_Lkas_FcwSysState": random.randint(0,65536),
+ "CF_Lkas_FcwCollisionWarning": random.randint(0,65536),
+ "CF_Lkas_FusionState": random.randint(0,65536),
+ "CF_Lkas_FcwOpt_USM": random.randint(0,65536),
+ "CF_Lkas_LdwsOpt_USM": random.randint(0,65536)
+ }
+ hud_alert = random.randint(0, 65536)
+ keep_stock = (random.randint(0, 2) % 2 == 0)
+ m_old = hyundaican.create_lkas11(self.hyundai_cp_old, car_fingerprint, apply_steer, steer_req, cnt, enabled,
+ lkas11, hud_alert, keep_stock)
+ m = hyundaican.create_lkas11(self.hyundai_cp, car_fingerprint, apply_steer, steer_req, cnt, enabled,
+ lkas11, hud_alert, keep_stock)
+ self.assertEqual(m_old, m)
+
+ clu11 = {
+ "CF_Clu_CruiseSwState": random.randint(0,65536),
+ "CF_Clu_CruiseSwMain": random.randint(0,65536),
+ "CF_Clu_SldMainSW": random.randint(0,65536),
+ "CF_Clu_ParityBit1": random.randint(0,65536),
+ "CF_Clu_VanzDecimal": random.randint(0,65536),
+ "CF_Clu_Vanz": random.randint(0,65536),
+ "CF_Clu_SPEED_UNIT": random.randint(0,65536),
+ "CF_Clu_DetentOut": random.randint(0,65536),
+ "CF_Clu_RheostatLevel": random.randint(0,65536),
+ "CF_Clu_CluInfo": random.randint(0,65536),
+ "CF_Clu_AmpInfo": random.randint(0,65536),
+ "CF_Clu_AliveCnt1": random.randint(0,65536),
+ }
+ button = random.randint(0, 65536)
+ m_old = hyundaican.create_clu11(self.hyundai_cp_old, clu11, button)
+ m = hyundaican.create_clu11(self.hyundai_cp, clu11, button)
+ self.assertEqual(m_old, m)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/can/tests/test_packer_subaru.py b/selfdrive/can/tests/test_packer_subaru.py
new file mode 100644
index 0000000000..65dd77cf83
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_subaru.py
@@ -0,0 +1,37 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+import selfdrive.car.subaru.subarucan as subarucan
+from selfdrive.car.subaru.values import CAR as subaru_car
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.subaru_cp_old = CANPackerOld("subaru_global_2017")
+ self.subaru_cp = CANPacker("subaru_global_2017")
+
+ def test_correctness(self):
+ # Test all cars' commands, randomize the params.
+ for _ in xrange(1000):
+ apply_steer = (random.randint(0, 2) % 2 == 0)
+ frame = random.randint(1, 65536)
+ steer_step = random.randint(1, 65536)
+ m_old = subarucan.create_steering_control(self.subaru_cp_old, subaru_car.IMPREZA, apply_steer, frame, steer_step)
+ m = subarucan.create_steering_control(self.subaru_cp, subaru_car.IMPREZA, apply_steer, frame, steer_step)
+ self.assertEqual(m_old, m)
+
+ m_old = subarucan.create_steering_status(self.subaru_cp_old, subaru_car.IMPREZA, apply_steer, frame, steer_step)
+ m = subarucan.create_steering_status(self.subaru_cp, subaru_car.IMPREZA, apply_steer, frame, steer_step)
+ self.assertEqual(m_old, m)
+
+ es_distance_msg = {}
+ pcm_cancel_cmd = (random.randint(0, 2) % 2 == 0)
+ m_old = subarucan.create_es_distance(self.subaru_cp_old, es_distance_msg, pcm_cancel_cmd)
+ m = subarucan.create_es_distance(self.subaru_cp, es_distance_msg, pcm_cancel_cmd)
+ self.assertEqual(m_old, m)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/can/tests/test_packer_toyota.py b/selfdrive/can/tests/test_packer_toyota.py
new file mode 100644
index 0000000000..42e36f3171
--- /dev/null
+++ b/selfdrive/can/tests/test_packer_toyota.py
@@ -0,0 +1,88 @@
+import unittest
+import random
+
+from selfdrive.can.tests.packer_old import CANPacker as CANPackerOld
+from selfdrive.can.packer import CANPacker
+from selfdrive.car.toyota.toyotacan import (
+ create_ipas_steer_command, create_steer_command, create_accel_command,
+ create_fcw_command, create_ui_command
+)
+from common.realtime import sec_since_boot
+
+
+class TestPackerMethods(unittest.TestCase):
+ def setUp(self):
+ self.cp_old = CANPackerOld("toyota_rav4_hybrid_2017_pt_generated")
+ self.cp = CANPacker("toyota_rav4_hybrid_2017_pt_generated")
+
+ def test_correctness(self):
+ # Test all commands, randomize the params.
+ for _ in xrange(1000):
+ # Toyota
+ steer = random.randint(-1, 1)
+ enabled = (random.randint(0, 2) % 2 == 0)
+ apgs_enabled = (random.randint(0, 2) % 2 == 0)
+ m_old = create_ipas_steer_command(self.cp_old, steer, enabled, apgs_enabled)
+ m = create_ipas_steer_command(self.cp, steer, enabled, apgs_enabled)
+ self.assertEqual(m_old, m)
+
+ steer = (random.randint(0, 2) % 2 == 0)
+ steer_req = (random.randint(0, 2) % 2 == 0)
+ raw_cnt = random.randint(1, 65536)
+ m_old = create_steer_command(self.cp_old, steer, steer_req, raw_cnt)
+ m = create_steer_command(self.cp, steer, steer_req, raw_cnt)
+ self.assertEqual(m_old, m)
+
+ accel = (random.randint(0, 2) % 2 == 0)
+ pcm_cancel = (random.randint(0, 2) % 2 == 0)
+ standstill_req = (random.randint(0, 2) % 2 == 0)
+ lead = (random.randint(0, 2) % 2 == 0)
+ m_old = create_accel_command(self.cp_old, accel, pcm_cancel, standstill_req, lead)
+ m = create_accel_command(self.cp, accel, pcm_cancel, standstill_req, lead)
+ self.assertEqual(m_old, m)
+
+ fcw = random.randint(1, 65536)
+ m_old = create_fcw_command(self.cp_old, fcw)
+ m = create_fcw_command(self.cp, fcw)
+ self.assertEqual(m_old, m)
+
+ steer = (random.randint(0, 2) % 2 == 0)
+ sound1 = random.randint(1, 65536)
+ sound2 = random.randint(1, 65536)
+ left_line = (random.randint(0, 2) % 2 == 0)
+ right_line = (random.randint(0, 2) % 2 == 0)
+ left_lane_depart = (random.randint(0, 2) % 2 == 0)
+ right_lane_depart = (random.randint(0, 2) % 2 == 0)
+ m_old = create_ui_command(self.cp_old, steer, sound1, sound2, left_line, right_line, left_lane_depart, right_lane_depart)
+ m = create_ui_command(self.cp, steer, sound1, sound2, left_line, right_line, left_lane_depart, right_lane_depart)
+ self.assertEqual(m_old, m)
+
+ def test_performance(self):
+ n1 = sec_since_boot()
+ recursions = 100000
+ steer = (random.randint(0, 2) % 2 == 0)
+ sound1 = random.randint(1, 65536)
+ sound2 = random.randint(1, 65536)
+ left_line = (random.randint(0, 2) % 2 == 0)
+ right_line = (random.randint(0, 2) % 2 == 0)
+ left_lane_depart = (random.randint(0, 2) % 2 == 0)
+ right_lane_depart = (random.randint(0, 2) % 2 == 0)
+
+ for _ in xrange(recursions):
+ create_ui_command(self.cp_old, steer, sound1, sound2, left_line, right_line, left_lane_depart, right_lane_depart)
+ n2 = sec_since_boot()
+ elapsed_old = n2 - n1
+
+ # print('Old API, elapsed time: {} secs'.format(elapsed_old))
+ n1 = sec_since_boot()
+ for _ in xrange(recursions):
+ create_ui_command(self.cp, steer, sound1, sound2, left_line, right_line, left_lane_depart, right_lane_depart)
+ n2 = sec_since_boot()
+ elapsed_new = n2 - n1
+ # print('New API, elapsed time: {} secs'.format(elapsed_new))
+ self.assertTrue(elapsed_new < elapsed_old / 2)
+
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py
index 7db36634c0..c6a1f9d293 100644
--- a/selfdrive/car/chrysler/carcontroller.py
+++ b/selfdrive/car/chrysler/carcontroller.py
@@ -97,4 +97,4 @@ class CarController(object):
self.ccframe += 1
self.prev_frame = frame
- sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py
index fd3c081f3d..94effcf931 100644
--- a/selfdrive/car/chrysler/carstate.py
+++ b/selfdrive/car/chrysler/carstate.py
@@ -1,7 +1,6 @@
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):
@@ -90,10 +89,10 @@ class CarState(object):
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_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
@@ -127,7 +126,7 @@ class CarState(object):
# Kalman filter
if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
- self.v_ego_kf.x = np.matrix([[v_wheel], [0.0]])
+ self.v_ego_kf.x = [[v_wheel], [0.0]]
self.v_ego_raw = v_wheel
v_ego_x = self.v_ego_kf.update(v_wheel)
diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py
index e0551ef0cf..2c3d7455a0 100755
--- a/selfdrive/car/chrysler/interface.py
+++ b/selfdrive/car/chrysler/interface.py
@@ -70,12 +70,12 @@ class CarInterface(object):
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.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15,0.30], [0.03,0.05]]
+ ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
ret.steerActuatorDelay = 0.1
ret.steerRateCost = 0.7
@@ -86,8 +86,6 @@ class CarInterface(object):
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
@@ -129,10 +127,12 @@ class CarInterface(object):
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]
+ ret.longitudinalTuning.deadzoneBP = [0., 9.]
+ ret.longitudinalTuning.deadzoneV = [0., .15]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.54, 0.36]
return ret
diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py
index 4636b89a31..c3e1c35805 100644
--- a/selfdrive/car/chrysler/values.py
+++ b/selfdrive/car/chrysler/values.py
@@ -34,6 +34,10 @@ FINGERPRINTS = {
# Based on 0607d2516fc2148f|2019-02-13--23-03-16
{
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: 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, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 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, 1537: 8
+ },
+ # Based on 3c7ce223e3571b54|2019-05-11--20-16-14
+ {
+ 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: 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, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 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, 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, 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, 1562: 8, 1570: 8
}
],
CAR.JEEP_CHEROKEE: [
diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py
index 5a8f1f142c..2c7a27eb3a 100644
--- a/selfdrive/car/ford/carstate.py
+++ b/selfdrive/car/ford/carstate.py
@@ -46,10 +46,10 @@ class CarState(object):
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_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):
@@ -69,7 +69,7 @@ class CarState(object):
# Kalman filter
if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
- self.v_ego_kf.x = np.matrix([[v_wheel], [0.0]])
+ self.v_ego_kf.x = [[v_wheel], [0.0]]
self.v_ego_raw = v_wheel
v_ego_x = self.v_ego_kf.update(v_wheel)
diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py
index 25e4d2b9cc..a46681eb4b 100755
--- a/selfdrive/car/ford/interface.py
+++ b/selfdrive/car/ford/interface.py
@@ -69,12 +69,12 @@ class CarInterface(object):
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01], [0.005]] # TODO: tune this
+ ret.lateralTuning.pid.kf = 1. / MAX_ANGLE # MAX Steer angle to normalize FF
ret.steerActuatorDelay = 0.1 # Default delay, not measured yet
ret.steerRateCost = 1.0
@@ -84,8 +84,6 @@ class CarInterface(object):
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.
@@ -126,10 +124,12 @@ class CarInterface(object):
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]
+ ret.longitudinalTuning.deadzoneBP = [0., 9.]
+ ret.longitudinalTuning.deadzoneV = [0., .15]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.54, 0.36]
return ret
diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py
index 67b2405364..26cfd84d35 100644
--- a/selfdrive/car/gm/carcontroller.py
+++ b/selfdrive/car/gm/carcontroller.py
@@ -195,4 +195,4 @@ class CarController(object):
# issued for the same chime type and duration
self.chime = chime
- sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py
index ae97a38b9c..7a18f320cf 100644
--- a/selfdrive/car/gm/carstate.py
+++ b/selfdrive/car/gm/carstate.py
@@ -63,10 +63,10 @@ class CarState(object):
# 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_kf = KF1D(x0=[[0.], [0.]],
+ A=[[1., dt], [0., 1.]],
+ C=[1., 0.],
+ K=[[0.12287673], [0.29666309]])
self.v_ego = 0.
def update(self, pt_cp):
diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py
index d5afffbaa9..a21b12d315 100755
--- a/selfdrive/car/gm/interface.py
+++ b/selfdrive/car/gm/interface.py
@@ -4,7 +4,8 @@ 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, SUPERCRUISE_CARS
+from selfdrive.car.gm.values import DBC, CAR, STOCK_CONTROL_MSGS, AUDIO_HUD, \
+ SUPERCRUISE_CARS, AccState
from selfdrive.car.gm.carstate import CarState, CruiseButtons, get_powertrain_can_parser
try:
@@ -162,25 +163,24 @@ class CarInterface(object):
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]]
+ ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594
- ret.steerMaxBP = [0.] # m/s
+ 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.longitudinalTuning.kpBP = [5., 35.]
+ ret.longitudinalTuning.kpV = [2.4, 1.5]
+ ret.longitudinalTuning.kiBP = [0.]
+ ret.longitudinalTuning.kiV = [0.36]
+ ret.longitudinalTuning.deadzoneBP = [0.]
+ ret.longitudinalTuning.deadzoneV = [0.]
ret.steerLimitAlert = True
@@ -231,7 +231,7 @@ class CarInterface(object):
# cruise state
ret.cruiseState.available = bool(self.CS.main_on)
- cruiseEnabled = self.CS.pcm_acc_status != 0
+ cruiseEnabled = self.CS.pcm_acc_status != AccState.OFF
ret.cruiseState.enabled = cruiseEnabled
ret.cruiseState.standstill = self.CS.pcm_acc_status == 4
@@ -323,6 +323,8 @@ class CarInterface(object):
events.append(create_event('pedalPressed', [ET.PRE_ENABLE]))
if ret.cruiseState.standstill:
events.append(create_event('resumeRequired', [ET.WARNING]))
+ if self.CS.pcm_acc_status == AccState.FAULTED:
+ events.append(create_event('controlsFailed', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE]))
# handle button presses
for b in ret.buttonEvents:
diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py
index f6aa0658ff..b41919acb9 100644
--- a/selfdrive/car/gm/values.py
+++ b/selfdrive/car/gm/values.py
@@ -30,6 +30,12 @@ class CM:
LOW_CHIME = 0x86
HIGH_CHIME = 0x87
+class AccState:
+ OFF = 0
+ ACTIVE = 1
+ FAULTED = 3
+ STANDSTILL = 4
+
AUDIO_HUD = {
AudibleAlert.none: (0, 0),
AudibleAlert.chimeEngage: (CM.HIGH_CHIME, 1),
diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py
index 7167583136..a164f399f9 100644
--- a/selfdrive/car/honda/carcontroller.py
+++ b/selfdrive/car/honda/carcontroller.py
@@ -184,4 +184,4 @@ class CarController(object):
# This prevents unexpected pedal range rescaling
can_sends.append(create_gas_command(self.packer, apply_gas, idx))
- sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py
index b8164e8c52..72bca7e3e7 100644
--- a/selfdrive/car/honda/carstate.py
+++ b/selfdrive/car/honda/carstate.py
@@ -192,7 +192,7 @@ class CarState(object):
# 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]],
+ C=[1.0, 0.0],
K=[[0.12287673], [0.29666309]])
self.v_ego = 0.0
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index 6c4b4a7672..8c3a2bd76a 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -183,9 +183,8 @@ class CarInterface(object):
# 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
+ ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward
if candidate in [CAR.CIVIC, CAR.CIVIC_BOSCH]:
stop_and_go = True
@@ -197,13 +196,13 @@ class CarInterface(object):
# 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']
if is_fw_modified:
- ret.steerKf = 0.00004
+ ret.lateralTuning.pid.kf = 0.00004
- ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]]
- ret.longitudinalKpBP = [0., 5., 35.]
- ret.longitudinalKpV = [3.6, 2.4, 1.5]
- ret.longitudinalKiBP = [0., 35.]
- ret.longitudinalKiV = [0.54, 0.36]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.54, 0.36]
elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH):
stop_and_go = True
@@ -214,11 +213,11 @@ class CarInterface(object):
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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.ACURA_ILX:
stop_and_go = False
@@ -227,11 +226,11 @@ class CarInterface(object):
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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.CRV:
stop_and_go = False
@@ -240,11 +239,11 @@ class CarInterface(object):
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.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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.CRV_5G:
stop_and_go = True
@@ -254,11 +253,11 @@ class CarInterface(object):
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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.CRV_HYBRID:
stop_and_go = True
@@ -268,11 +267,11 @@ class CarInterface(object):
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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.ACURA_RDX:
stop_and_go = False
@@ -281,11 +280,11 @@ class CarInterface(object):
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.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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.ODYSSEY:
stop_and_go = False
@@ -294,11 +293,11 @@ class CarInterface(object):
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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.45], [0.135]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.ODYSSEY_CHN:
stop_and_go = False
@@ -307,11 +306,11 @@ class CarInterface(object):
ret.centerToFront = ret.wheelbase * 0.41 # from CAR.ODYSSEY
ret.steerRatio = 14.35 # from CAR.ODYSSEY
tire_stiffness_factor = 0.82 # from CAR.ODYSSEY
- 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]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.45], [0.135]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate in (CAR.PILOT, CAR.PILOT_2019):
stop_and_go = False
@@ -320,11 +319,11 @@ class CarInterface(object):
ret.centerToFront = ret.wheelbase * 0.41
ret.steerRatio = 16.0 # as spec
tire_stiffness_factor = 0.444 # not optimized yet
- ret.steerKpV, ret.steerKiV = [[0.38], [0.11]]
- ret.longitudinalKpBP = [0., 5., 35.]
- ret.longitudinalKpV = [1.2, 0.8, 0.5]
- ret.longitudinalKiBP = [0., 35.]
- ret.longitudinalKiV = [0.18, 0.12]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
elif candidate == CAR.RIDGELINE:
stop_and_go = False
@@ -333,11 +332,11 @@ class CarInterface(object):
ret.centerToFront = ret.wheelbase * 0.41
ret.steerRatio = 15.59 # as spec
tire_stiffness_factor = 0.444 # not optimized yet
- ret.steerKpV, ret.steerKiV = [[0.38], [0.11]]
- ret.longitudinalKpBP = [0., 5., 35.]
- ret.longitudinalKpV = [1.2, 0.8, 0.5]
- ret.longitudinalKiBP = [0., 35.]
- ret.longitudinalKiV = [0.18, 0.12]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
else:
raise ValueError("unsupported car %s" % candidate)
@@ -376,8 +375,8 @@ class CarInterface(object):
ret.brakeMaxBP = [5., 20.] # m/s
ret.brakeMaxV = [1., 0.8] # max brake allowed
- ret.longPidDeadzoneBP = [0.]
- ret.longPidDeadzoneV = [0.]
+ ret.longitudinalTuning.deadzoneBP = [0.]
+ ret.longitudinalTuning.deadzoneV = [0.]
ret.stoppingControl = True
ret.steerLimitAlert = True
diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py
index 627e27b4c4..82dbc0aed8 100644
--- a/selfdrive/car/hyundai/carcontroller.py
+++ b/selfdrive/car/hyundai/carcontroller.py
@@ -71,6 +71,6 @@ class CarController(object):
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())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
self.cnt += 1
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index bd3e63740c..041360f4bb 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -2,7 +2,6 @@ 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):
@@ -133,10 +132,10 @@ class CarState(object):
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_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
self.left_blinker_on = 0
self.left_blinker_flash = 0
@@ -173,7 +172,7 @@ class CarState(object):
# Kalman filter, even though Hyundai raw wheel speed is heaviliy filtered by default
if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
- self.v_ego_kf.x = np.matrix([[v_wheel], [0.0]])
+ self.v_ego_kf.x = [[v_wheel], [0.0]]
self.v_ego_raw = v_wheel
v_ego_x = self.v_ego_kf.update(v_wheel)
diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py
index 6186565584..cc5d95d06d 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -74,7 +74,7 @@ class CarInterface(object):
ret.steerRateCost = 0.5
if candidate == CAR.SANTA_FE:
- ret.steerKf = 0.00005
+ ret.lateralTuning.pid.kf = 0.00005
ret.mass = 3982 * CV.LB_TO_KG + std_cargo
ret.wheelbase = 2.766
@@ -82,56 +82,58 @@ class CarInterface(object):
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]]
ret.minSteerSpeed = 0.
elif candidate == CAR.KIA_SORENTO:
- ret.steerKf = 0.00005
+ ret.lateralTuning.pid.kf = 0.00005
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
ret.minSteerSpeed = 0.
elif candidate == CAR.ELANTRA:
- ret.steerKf = 0.00006
+ ret.lateralTuning.pid.kf = 0.00006
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
ret.minSteerSpeed = 32 * CV.MPH_TO_MS
elif candidate == CAR.GENESIS:
- ret.steerKf = 0.00005
+ ret.lateralTuning.pid.kf = 0.00005
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]]
ret.minSteerSpeed = 35 * CV.MPH_TO_MS
elif candidate == CAR.KIA_OPTIMA:
- ret.steerKf = 0.00005
+ ret.lateralTuning.pid.kf = 0.00005
ret.mass = 3558 * CV.LB_TO_KG
ret.wheelbase = 2.80
ret.steerRatio = 13.75
tire_stiffness_factor = 0.5
- ret.steerKiBP, ret.steerKpBP = [[0.], [0.]]
- ret.steerKpV, ret.steerKiV = [[0.25], [0.05]]
+ ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
elif candidate == CAR.KIA_STINGER:
- ret.steerKf = 0.00005
+ ret.lateralTuning.pid.kf = 0.00005
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.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[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.longitudinalTuning.kpBP = [0.]
+ ret.longitudinalTuning.kpV = [0.]
+ ret.longitudinalTuning.kiBP = [0.]
+ ret.longitudinalTuning.kiV = [0.]
+ ret.longitudinalTuning.deadzoneBP = [0.]
+ ret.longitudinalTuning.deadzoneV = [0.]
ret.centerToFront = ret.wheelbase * 0.4
@@ -163,8 +165,6 @@ class CarInterface(object):
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
diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py
index 3a5e05257c..bf9b8a5e74 100755
--- a/selfdrive/car/mock/interface.py
+++ b/selfdrive/car/mock/interface.py
@@ -56,8 +56,6 @@ class CarInterface(object):
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.
@@ -69,10 +67,12 @@ class CarInterface(object):
ret.brakeMaxBP = [0.]
ret.brakeMaxV = [0.]
- ret.longitudinalKpBP = [0.]
- ret.longitudinalKpV = [0.]
- ret.longitudinalKiBP = [0.]
- ret.longitudinalKiV = [0.]
+ ret.longitudinalTuning.kpBP = [0.]
+ ret.longitudinalTuning.kpV = [0.]
+ ret.longitudinalTuning.kiBP = [0.]
+ ret.longitudinalTuning.kiV = [0.]
+ ret.longitudinalTuning.deadzoneBP = [0.]
+ ret.longitudinalTuning.deadzoneV = [0.]
ret.steerActuatorDelay = 0.
return ret
diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py
index 33a0fde868..98deb56467 100644
--- a/selfdrive/car/subaru/carcontroller.py
+++ b/selfdrive/car/subaru/carcontroller.py
@@ -73,4 +73,4 @@ class CarController(object):
can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert))
self.es_lkas_cnt = CS.es_lkas_msg["Counter"]
- sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py
index 38d2fe4794..722b171182 100644
--- a/selfdrive/car/subaru/carstate.py
+++ b/selfdrive/car/subaru/carstate.py
@@ -1,5 +1,4 @@
import copy
-import numpy as np
from common.kalman.simple_kalman import KF1D
from selfdrive.config import Conversions as CV
from selfdrive.can.parser import CANParser
@@ -26,6 +25,7 @@ def get_powertrain_can_parser(CP):
("DOOR_OPEN_FL", "BodyInfo", 1),
("DOOR_OPEN_RR", "BodyInfo", 1),
("DOOR_OPEN_RL", "BodyInfo", 1),
+ ("Units", "Dash_State", 1),
]
checks = [
@@ -61,6 +61,10 @@ def get_camera_can_parser(CP):
("Signal3", "ES_LKAS_State", 0),
("LKAS_ENABLE_2", "ES_LKAS_State", 0),
("Signal4", "ES_LKAS_State", 0),
+ ("LKAS_Left_Line_Visible", "ES_LKAS_State", 0),
+ ("Signal6", "ES_LKAS_State", 0),
+ ("LKAS_Right_Line_Visible", "ES_LKAS_State", 0),
+ ("Signal7", "ES_LKAS_State", 0),
("FCW_Cont_Beep", "ES_LKAS_State", 0),
("FCW_Repeated_Beep", "ES_LKAS_State", 0),
("Throttle_Management_Activated", "ES_LKAS_State", 0),
@@ -92,10 +96,10 @@ class CarState(object):
# 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_kf = KF1D(x0=[[0.], [0.]],
+ A=[[1., dt], [0., 1.]],
+ C=[1., 0.],
+ K=[[0.12287673], [0.29666309]])
self.v_ego = 0.
def update(self, cp, cp_cam):
@@ -114,12 +118,15 @@ class CarState(object):
self.v_wheel_rl = cp.vl["Wheel_Speeds"]['RL'] * CV.KPH_TO_MS
self.v_wheel_rr = cp.vl["Wheel_Speeds"]['RR'] * CV.KPH_TO_MS
- self.v_cruise_pcm = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.MPH_TO_KPH
+ self.v_cruise_pcm = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed']
+ # 1 = imperial, 6 = metric
+ if cp.vl["Dash_State"]['Units'] == 1:
+ self.v_cruise_pcm *= CV.MPH_TO_KPH
v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4.
# Kalman filter, even though Hyundai raw wheel speed is heaviliy filtered by default
if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
- self.v_ego_kf.x = np.matrix([[v_wheel], [0.0]])
+ self.v_ego_kf.x = [[v_wheel], [0.0]]
self.v_ego_raw = v_wheel
v_ego_x = self.v_ego_kf.update(v_wheel)
diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py
index ef3da2f398..8de0760b4b 100644
--- a/selfdrive/car/subaru/interface.py
+++ b/selfdrive/car/subaru/interface.py
@@ -66,9 +66,9 @@ class CarInterface(object):
ret.steerRatio = 15
tire_stiffness_factor = 1.0
ret.steerActuatorDelay = 0.4 # end-to-end angle controller
- ret.steerKf = 0.00005
- ret.steerKiBP, ret.steerKpBP = [[0., 20.], [0., 20.]]
- ret.steerKpV, ret.steerKiV = [[0.2, 0.3], [0.02, 0.03]]
+ ret.lateralTuning.pid.kf = 0.00005
+ ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]]
ret.steerMaxBP = [0.] # m/s
ret.steerMaxV = [1.]
@@ -81,12 +81,12 @@ class CarInterface(object):
ret.gasMaxV = [0.]
ret.brakeMaxBP = [0.]
ret.brakeMaxV = [0.]
- ret.longPidDeadzoneBP = [0.]
- ret.longPidDeadzoneV = [0.]
- ret.longitudinalKpBP = [0.]
- ret.longitudinalKpV = [0.]
- ret.longitudinalKiBP = [0.]
- ret.longitudinalKiV = [0.]
+ ret.longitudinalTuning.deadzoneBP = [0.]
+ ret.longitudinalTuning.deadzoneV = [0.]
+ ret.longitudinalTuning.kpBP = [0.]
+ ret.longitudinalTuning.kpV = [0.]
+ ret.longitudinalTuning.kiBP = [0.]
+ ret.longitudinalTuning.kiV = [0.]
# end from gm
diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py
index 18b8929564..0e444d7361 100644
--- a/selfdrive/car/subaru/values.py
+++ b/selfdrive/car/subaru/values.py
@@ -6,6 +6,10 @@ class CAR:
FINGERPRINTS = {
CAR.IMPREZA: [{
2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8
+ },
+ # Crosstrek 2018 (same platform as Subaru)
+ {
+ 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 256: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8
}],
}
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index d69636d32d..0bd5d90023 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -7,7 +7,7 @@ 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.car.toyota.values import ECU, STATIC_MSGS, TSSP2_CAR
from selfdrive.can.packer import CANPacker
VisualAlert = car.CarControl.HUDControl.VisualAlert
@@ -249,7 +249,7 @@ class CarController(object):
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, left_lane_depart, right_lane_depart))
- if frame % 100 == 0 and ECU.DSU in self.fake_ecus:
+ if frame % 100 == 0 and ECU.DSU in self.fake_ecus and self.car_fingerprint not in TSSP2_CAR:
can_sends.append(create_fcw_command(self.packer, fcw))
#*** static msgs ***
@@ -271,4 +271,4 @@ class CarController(object):
can_sends.append(make_can_msg(addr, vl, bus, False))
- sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
+ sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan'))
diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py
index 02debc47bf..88471b61a5 100644
--- a/selfdrive/car/toyota/carstate.py
+++ b/selfdrive/car/toyota/carstate.py
@@ -97,10 +97,10 @@ class CarState(object):
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_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):
@@ -133,7 +133,7 @@ class CarState(object):
# Kalman filter
if abs(v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed
- self.v_ego_kf.x = np.matrix([[v_wheel], [0.0]])
+ self.v_ego_kf.x = [[v_wheel], [0.0]]
self.v_ego_raw = v_wheel
v_ego_x = self.v_ego_kf.update(v_wheel)
diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py
index 0fe0d0821a..ea5b748d53 100755
--- a/selfdrive/car/toyota/interface.py
+++ b/selfdrive/car/toyota/interface.py
@@ -5,7 +5,7 @@ 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.car.toyota.values import ECU, check_ecu_msgs, CAR, NO_STOP_TIMER_CAR
from selfdrive.swaglog import cloudlog
try:
@@ -73,8 +73,10 @@ class CarInterface(object):
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.lateralTuning.init('pid')
+ ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
if candidate == CAR.PRIUS:
stop_and_go = True
@@ -83,10 +85,15 @@ class CarInterface(object):
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
+
+ ret.lateralTuning.init('indi')
+ ret.lateralTuning.indi.innerLoopGain = 4.0
+ ret.lateralTuning.indi.outerLoopGain = 3.0
+ ret.lateralTuning.indi.timeConstant = 1.0
+ ret.lateralTuning.indi.actuatorEffectiveness = 1.0
+
+ ret.steerActuatorDelay = 0.5
+ ret.steerRateCost = 0.5
elif candidate in [CAR.RAV4, CAR.RAV4H]:
stop_and_go = True if (candidate in CAR.RAV4H) else False
@@ -95,8 +102,8 @@ class CarInterface(object):
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
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.05]]
+ ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
elif candidate == CAR.COROLLA:
stop_and_go = False
@@ -105,8 +112,8 @@ class CarInterface(object):
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
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]]
+ ret.lateralTuning.pid.kf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594
elif candidate == CAR.LEXUS_RXH:
stop_and_go = True
@@ -115,8 +122,8 @@ class CarInterface(object):
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
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]]
+ ret.lateralTuning.pid.kf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
elif candidate in [CAR.CHR, CAR.CHRH]:
stop_and_go = True
@@ -125,8 +132,8 @@ class CarInterface(object):
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
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.723], [0.0428]]
+ ret.lateralTuning.pid.kf = 0.00006
elif candidate in [CAR.CAMRY, CAR.CAMRYH]:
stop_and_go = True
@@ -135,8 +142,8 @@ class CarInterface(object):
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
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.1]]
+ ret.lateralTuning.pid.kf = 0.00006
elif candidate in [CAR.HIGHLANDER, CAR.HIGHLANDERH]:
stop_and_go = True
@@ -145,15 +152,42 @@ class CarInterface(object):
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.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.05]]
+ ret.lateralTuning.pid.kf = 0.00006
+
+ elif candidate == CAR.AVALON:
+ stop_and_go = False
+ ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file
+ ret.wheelbase = 2.82
+ ret.steerRatio = 14.8 #Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download
+ tire_stiffness_factor = 0.7983
+ ret.mass = 3505 * CV.LB_TO_KG + std_cargo # mean between normal and hybrid
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.17], [0.03]]
+ ret.lateralTuning.pid.kf = 0.00006
+
+ elif candidate == CAR.RAV4_2019:
+ stop_and_go = True
+ ret.safetyParam = 100
+ ret.wheelbase = 2.68986
+ ret.steerRatio = 14.3
+ tire_stiffness_factor = 0.7933
+ ret.mass = 3370. * CV.LB_TO_KG + std_cargo
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]]
+ ret.lateralTuning.pid.kf = 0.00007818594
+
+ elif candidate == CAR.COROLLA_HATCH:
+ stop_and_go = True
+ ret.safetyParam = 100
+ ret.wheelbase = 2.63906
+ ret.steerRatio = 13.9
+ tire_stiffness_factor = 0.444
+ ret.mass = 3060. * CV.LB_TO_KG + std_cargo
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]]
+ ret.lateralTuning.pid.kf = 0.00007818594
ret.steerRateCost = 1.
ret.centerToFront = ret.wheelbase * 0.44
- ret.longPidDeadzoneBP = [0., 9.]
- ret.longPidDeadzoneV = [0., .15]
-
#detect the Pedal address
ret.enableGasInterceptor = 0x201 in fingerprint
@@ -196,21 +230,24 @@ class CarInterface(object):
cloudlog.warn("ECU Gas Interceptor: %r", ret.enableGasInterceptor)
ret.steerLimitAlert = False
- ret.longitudinalKpBP = [0., 5., 35.]
- ret.longitudinalKiBP = [0., 35.]
+
+ ret.longitudinalTuning.deadzoneBP = [0., 9.]
+ ret.longitudinalTuning.deadzoneV = [0., .15]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kiBP = [0., 35.]
ret.stoppingControl = False
ret.startAccel = 0.0
if ret.enableGasInterceptor:
ret.gasMaxBP = [0., 9., 35]
ret.gasMaxV = [0.2, 0.5, 0.7]
- ret.longitudinalKpV = [1.2, 0.8, 0.5]
- ret.longitudinalKiV = [0.18, 0.12]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
+ ret.longitudinalTuning.kiV = [0.18, 0.12]
else:
ret.gasMaxBP = [0.]
ret.gasMaxV = [0.5]
- ret.longitudinalKpV = [3.6, 2.4, 1.5]
- ret.longitudinalKiV = [0.54, 0.36]
+ ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
+ ret.longitudinalTuning.kiV = [0.54, 0.36]
return ret
@@ -270,7 +307,7 @@ class CarInterface(object):
ret.cruiseState.available = bool(self.CS.main_on)
ret.cruiseState.speedOffset = 0.
- if self.CP.carFingerprint in [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER] or self.CP.enableGasInterceptor:
+ if self.CP.carFingerprint in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor:
# ignore standstill in hybrid vehicles, since pcm allows to restart without
# receiving any special command
# also if interceptor is detected
@@ -369,7 +406,7 @@ class CarInterface(object):
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,
+ c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, c.hudControl.leadVisible,
c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart)
self.frame += 1
diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py
index 054ce0b7be..fc6f3e5234 100755
--- a/selfdrive/car/toyota/radar_interface.py
+++ b/selfdrive/car/toyota/radar_interface.py
@@ -7,39 +7,48 @@ 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
+from selfdrive.car.toyota.values import NO_DSU_CAR, DBC, TSSP2_CAR
+def _create_radard_can_parser(car_fingerprint):
+ dbc_f = DBC[car_fingerprint]['radar']
-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'
+ if car_fingerprint in TSSP2_CAR:
+ RADAR_A_MSGS = list(range(0x180, 0x190))
+ RADAR_B_MSGS = list(range(0x190, 0x1a0))
+ else:
+ RADAR_A_MSGS = list(range(0x210, 0x220))
+ RADAR_B_MSGS = list(range(0x220, 0x230))
msg_a_n = len(RADAR_A_MSGS)
msg_b_n = len(RADAR_B_MSGS)
- signals = list(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))
+ 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 = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + 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()
+ if CP.carFingerprint in TSSP2_CAR:
+ self.RADAR_A_MSGS = list(range(0x180, 0x190))
+ self.RADAR_B_MSGS = list(range(0x190, 0x1a0))
+ else:
+ self.RADAR_A_MSGS = list(range(0x210, 0x220))
+ self.RADAR_B_MSGS = list(range(0x220, 0x230))
+
+ self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS}
+
+ self.rcp = _create_radard_can_parser(CP.carFingerprint)
self.no_dsu_car = CP.carFingerprint in NO_DSU_CAR
context = zmq.Context()
@@ -48,6 +57,7 @@ class RadarInterface(object):
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)
@@ -58,7 +68,7 @@ class RadarInterface(object):
while 1:
tm = int(sec_since_boot() * 1e9)
updated_messages.update(self.rcp.update(tm, True))
- if RADAR_B_MSGS[-1] in updated_messages:
+ if self.RADAR_B_MSGS[-1] in updated_messages:
break
errors = []
@@ -68,7 +78,7 @@ class RadarInterface(object):
ret.canMonoTimes = canMonoTimes
for ii in updated_messages:
- if ii in RADAR_A_MSGS:
+ if ii in self.RADAR_A_MSGS:
cpt = self.rcp.vl[ii]
if cpt['LONG_DIST'] >=255 or cpt['NEW_TRACK']:
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 72224334a4..52e3d1510c 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -12,6 +12,9 @@ class CAR:
CAMRYH = "TOYOTA CAMRY HYBRID 2018"
HIGHLANDER = "TOYOTA HIGHLANDER 2017"
HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018"
+ AVALON = "TOYOTA AVALON 2016"
+ RAV4_2019 = "TOYOTA RAV4 2019"
+ COROLLA_HATCH = "TOYOTA COROLLA HATCH 2019"
class ECU:
@@ -22,39 +25,39 @@ class ECU:
# 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'),
+ (0x130, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 0, 40, '\x06\x00'),
+ (0x414, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 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'),
+ (0x466, ECU.CAM, (CAR.COROLLA, CAR.AVALON), 1, 100, '\x24\x20\xB1'),
+ (0x489, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 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, CAR.AVALON), 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, CAR.AVALON), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'),
+ (0x4d3, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 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.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 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'),
+ (0x141, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 1, 2, '\x00\x00\x00\x46'),
+ (0x160, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'),
+ (0x161, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 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'),
+ (0x283, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 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'),
+ (0x344, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON), 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'),
+ (0x365, ECU.DSU, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON), 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'),
+ (0x366, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON), 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'),
+ (0x4CB, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON), 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'),
@@ -123,9 +126,9 @@ FINGERPRINTS = {
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 and LE with Blindspot Monitor
+ #SE, LE and LE with Blindspot Monitor
{
- 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, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 889: 8, 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, 983: 8, 984: 8, 993: 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, 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, 1237: 8, 1264: 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, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ 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, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 889: 8, 896: 8, 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, 983: 8, 984: 8, 993: 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, 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, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
},
#SL
{
@@ -141,6 +144,15 @@ FINGERPRINTS = {
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, 1263: 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
}],
+ CAR.AVALON: [{
+ 36: 8, 37: 8, 170: 8, 180: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 550: 8, 552: 4, 562: 6, 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, 905: 8, 911: 1, 916: 2, 921: 8, 933: 6, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 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, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 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, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ }],
+ CAR.RAV4_2019: [{
+ 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8,1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553:8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ }],
+ CAR.COROLLA_HATCH: [{
+ 36: 8, 37: 8, 114: 5, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8 , 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7 , 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000:8, 1001: 8, 1002: 8, 1017:8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059:1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
+ }]
}
STEER_THRESHOLD = 100
@@ -157,6 +169,11 @@ DBC = {
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'),
+ CAR.AVALON: dbc_dict('toyota_avalon_2017_pt_generated', 'toyota_prius_2017_adas'),
+ CAR.RAV4_2019: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_rav4_2019_adas'),
+ CAR.COROLLA_HATCH: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_rav4_2019_adas'),
}
NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]
+TSSP2_CAR = [CAR.RAV4_2019, CAR.COROLLA_HATCH]
+NO_STOP_TIMER_CAR = [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.RAV4_2019, CAR.COROLLA_HATCH] # no resume button press required
diff --git a/selfdrive/common/cereal.mk b/selfdrive/common/cereal.mk
index 46f23be551..0a3958a23f 100644
--- a/selfdrive/common/cereal.mk
+++ b/selfdrive/common/cereal.mk
@@ -5,11 +5,7 @@ UNAME_S ?= $(shell uname -s)
CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include
-ifeq ($(OPTEST),1)
-
-CEREAL_LIBS = -lcapnp -lkj
-
-else ifeq ($(UNAME_S),Darwin)
+ifeq ($(UNAME_S),Darwin)
CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/mac/include
CEREAL_LIBS = $(PHONELIBS)/capnp-cpp/mac/lib/libcapnp.a \
@@ -33,9 +29,9 @@ ifeq ($(CEREAL_LIBS),)
-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++
diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c
index 6f8f0a9a6c..01b8a0b6d9 100644
--- a/selfdrive/common/util.c
+++ b/selfdrive/common/util.c
@@ -26,6 +26,7 @@ void* read_file(const char* path, size_t* out_len) {
fclose(f);
if (num_read != 1) {
+ free(buf);
return NULL;
}
diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h
index fd8219990d..f2f73bbe08 100644
--- a/selfdrive/common/version.h
+++ b/selfdrive/common/version.h
@@ -1 +1 @@
-#define COMMA_VERSION "0.5.11-release"
+#define COMMA_VERSION "0.5.12-release"
diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py
index 31dcbef075..bbc90976b3 100755
--- a/selfdrive/controls/controlsd.py
+++ b/selfdrive/controls/controlsd.py
@@ -2,6 +2,8 @@
import gc
import zmq
import json
+from collections import defaultdict
+
from cereal import car, log
from common.numpy_fast import clip
from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper
@@ -19,7 +21,8 @@ from selfdrive.controls.lib.drive_helpers import learn_angle_model_bias, \
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.latcontrol_pid import LatControlPID
+from selfdrive.controls.lib.latcontrol_indi import LatControlINDI
from selfdrive.controls.lib.alertmanager import AlertManager
from selfdrive.controls.lib.vehicle_model import VehicleModel
from selfdrive.controls.lib.driver_monitor import DriverStatus
@@ -40,7 +43,7 @@ def isEnabled(state):
return (isActive(state) or state == State.preEnabled)
-def data_sample(CI, CC, plan_sock, path_plan_sock, thermal, calibration, health, driver_monitor,
+def data_sample(rcv_times, CI, CC, plan_sock, path_plan_sock, thermal, calibration, health, driver_monitor,
poller, cal_status, cal_perc, overtemp, free_space, low_battery,
driver_status, state, mismatch_counter, params, plan, path_plan):
"""Receive data from sockets and create events for battery, temperature and disk space"""
@@ -57,18 +60,21 @@ def data_sample(CI, CC, plan_sock, path_plan_sock, thermal, calibration, health,
dm = None
for socket, event in poller.poll(0):
+ msg = messaging.recv_one(socket)
+ rcv_times[msg.which()] = sec_since_boot()
+
if socket is thermal:
- td = messaging.recv_one(socket)
+ td = msg
elif socket is calibration:
- cal = messaging.recv_one(socket)
+ cal = msg
elif socket is health:
- hh = messaging.recv_one(socket)
+ hh = msg
elif socket is driver_monitor:
- dm = messaging.recv_one(socket)
+ dm = msg
elif socket is plan_sock:
- plan = messaging.recv_one(socket)
+ plan = msg
elif socket is path_plan_sock:
- path_plan = messaging.recv_one(socket)
+ path_plan = msg
if td is not None:
overtemp = td.thermal.thermalStatus >= ThermalStatus.red
@@ -202,7 +208,7 @@ def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM
return state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last
-def state_control(plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk,
+def state_control(rcv_times, plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk,
driver_status, LaC, LoC, VM, angle_model_bias, passive, is_metric, cal_perc):
"""Given the state, this function returns an actuators packet"""
@@ -246,11 +252,11 @@ def state_control(plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise
path_plan.cPoly, path_plan.cProb, CS.steeringAngle,
CS.steeringPressed)
- cur_time = sec_since_boot() # TODO: This won't work in replay
- mpc_time = plan.l20MonoTime / 1e9
+ cur_time = sec_since_boot()
+ radar_time = rcv_times['plan'] - plan.processingDelay # Subtract processing delay to get the original measurement time
_DT = 0.01 # 100Hz
- dt = min(cur_time - mpc_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps
+ dt = min(cur_time - radar_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps
a_acc_sol = plan.aStart + (dt / _DT_MPC) * (plan.aTarget - plan.aStart)
v_acc_sol = plan.vStart + dt * (a_acc_sol + plan.aStart) / 2.0
@@ -258,8 +264,8 @@ def state_control(plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise
actuators.gas, actuators.brake = LoC.update(active, CS.vEgo, CS.brakePressed, CS.standstill, CS.cruiseState.standstill,
v_cruise_kph, v_acc_sol, plan.vTargetFuture, a_acc_sol, CP)
# Steering PID loop and lateral MPC
- actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle,
- CS.steeringPressed, CP, VM, path_plan)
+ actuators.steer, actuators.steerAngle, lac_log = LaC.update(active, CS.vEgo, CS.steeringAngle, CS.steeringRate,
+ CS.steeringPressed, CP, VM, path_plan)
# Send a "steering required alert" if saturation count has reached the limit
if LaC.sat_flag and CP.steerLimitAlert:
@@ -278,12 +284,12 @@ def state_control(plan, path_plan, CS, CP, state, events, v_cruise_kph, v_cruise
AM.process_alerts(sec_since_boot())
- return actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc_sol, a_acc_sol
+ return actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc_sol, a_acc_sol, lac_log
def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate,
carcontrol, live100, AM, driver_status,
- LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc):
+ LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc, lac_log):
"""Send actuators and hud commands to the car, send live100 and MPC logging"""
plan_ts = plan.logMonoTime
plan = plan.plan
@@ -361,9 +367,6 @@ def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruis
"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(v_acc),
"aTarget": float(a_acc),
"jerkFactor": float(plan.jerkFactor),
@@ -372,10 +375,15 @@ def data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruis
"vCurvature": plan.vCurvature,
"decelForTurn": plan.decelForTurn,
"cumLagMs": -rk.remaining * 1000.,
- "startMonoTime": start_time,
+ "startMonoTime": int(start_time * 1e9),
"mapValid": plan.mapValid,
"forceDecel": bool(force_decel),
}
+
+ if CP.lateralTuning.which() == 'pid':
+ dat.live100.lateralControlState.pidState = lac_log
+ else:
+ dat.live100.lateralControlState.indiState = lac_log
live100.send(dat.to_bytes())
# carState
@@ -443,7 +451,12 @@ def controlsd_thread(gctx=None, rate=100):
LoC = LongControl(CP, CI.compute_gb)
VM = VehicleModel(CP)
- LaC = LatControl(CP)
+
+ if CP.lateralTuning.which() == 'pid':
+ LaC = LatControlPID(CP)
+ else:
+ LaC = LatControlINDI(CP)
+
AM = AlertManager()
driver_status = DriverStatus()
@@ -465,6 +478,8 @@ def controlsd_thread(gctx=None, rate=100):
mismatch_counter = 0
low_battery = False
+ rcv_times = defaultdict(int)
+
plan = messaging.new_message()
plan.init('plan')
path_plan = messaging.new_message()
@@ -485,23 +500,30 @@ def controlsd_thread(gctx=None, rate=100):
prof = Profiler(False) # off by default
while True:
- start_time = int(sec_since_boot() * 1e9)
+ start_time = sec_since_boot()
prof.checkpoint("Ratekeeper", ignore=True)
# Sample data and compute car events
CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter, plan, path_plan =\
- data_sample(CI, CC, plan_sock, path_plan_sock, thermal, cal, health, driver_monitor,
+ data_sample(rcv_times, CI, CC, plan_sock, path_plan_sock, thermal, cal, health, driver_monitor,
poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status,
state, mismatch_counter, params, plan, path_plan)
prof.checkpoint("Sample")
- path_plan_age = (start_time - path_plan.logMonoTime) / 1e9
- plan_age = (start_time - plan.logMonoTime) / 1e9
+ # Create alerts
+ path_plan_age = start_time - rcv_times['pathPlan']
+ plan_age = start_time - rcv_times['plan']
+
if not path_plan.pathPlan.valid or plan_age > 0.5 or path_plan_age > 0.5:
events.append(create_event('plannerError', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
if not path_plan.pathPlan.paramsValid:
events.append(create_event('vehicleModelInvalid', [ET.WARNING]))
- events += list(plan.plan.events)
+ if not path_plan.pathPlan.modelValid:
+ events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
+ if not plan.plan.radarValid:
+ events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
+ if plan.plan.radarCommIssue:
+ events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
# Only allow engagement with brake pressed when stopped behind another stopped car
if CS.brakePressed and plan.plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3:
@@ -514,8 +536,8 @@ def controlsd_thread(gctx=None, rate=100):
prof.checkpoint("State transition")
# Compute actuators (runs PID loops and lateral MPC)
- actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc, a_acc = \
- state_control(plan.plan, path_plan.pathPlan, CS, CP, state, events, v_cruise_kph,
+ actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc, a_acc, lac_log = \
+ state_control(rcv_times, plan.plan, path_plan.pathPlan, CS, CP, state, events, v_cruise_kph,
v_cruise_kph_last, AM, rk, driver_status,
LaC, LoC, VM, angle_model_bias, passive, is_metric, cal_perc)
@@ -523,7 +545,7 @@ def controlsd_thread(gctx=None, rate=100):
# Publish data
CC = data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol,
- live100, AM, driver_status, LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc)
+ live100, AM, driver_status, LaC, LoC, angle_model_bias, passive, start_time, v_acc, a_acc, lac_log)
prof.checkpoint("Sent")
rk.keep_time() # Run at 100Hz
diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py
index 15d5a202f7..28e35dddf8 100644
--- a/selfdrive/controls/lib/drive_helpers.py
+++ b/selfdrive/controls/lib/drive_helpers.py
@@ -1,7 +1,9 @@
from cereal import car
-from common.numpy_fast import clip
+from common.numpy_fast import clip, interp
from selfdrive.config import Conversions as CV
+DT = 0.01 # Controlsd runs at 100Hz
+
# kph
V_CRUISE_MAX = 144
V_CRUISE_MIN = 8
@@ -55,6 +57,10 @@ def rate_limit(new_value, last_value, dw_step, up_step):
return clip(new_value, last_value + dw_step, last_value + up_step)
+def get_steer_max(CP, v_ego):
+ return interp(v_ego, CP.steerMaxBP, CP.steerMaxV)
+
+
def learn_angle_model_bias(lateral_control, v_ego, angle_model_bias, 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
diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py
index 9af3cb1b10..814d77a6a6 100644
--- a/selfdrive/controls/lib/driver_monitor.py
+++ b/selfdrive/controls/lib/driver_monitor.py
@@ -16,6 +16,7 @@ _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
+_YAW_NATURAL_OFFSET = 0.08 # people don't seem to look straight when they drive relaxed, rather a bit to the right (center of car)
_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
@@ -89,7 +90,7 @@ class DriverStatus():
def _is_driver_distracted(self, pose):
# to be tuned and to learn the driver's normal pose
pitch_error = pose.pitch - _PITCH_NATURAL_OFFSET
- yaw_error = pose.yaw
+ yaw_error = pose.yaw - _YAW_NATURAL_OFFSET
# add positive pitch allowance
if pitch_error > 0.:
pitch_error = max(pitch_error - _PITCH_POS_ALLOWANCE, 0.)
diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py
new file mode 100644
index 0000000000..2e95489bc5
--- /dev/null
+++ b/selfdrive/controls/lib/latcontrol_indi.py
@@ -0,0 +1,104 @@
+import math
+import numpy as np
+
+from selfdrive.car.toyota.carcontroller import SteerLimitParams
+from selfdrive.car import apply_toyota_steer_torque_limits
+from selfdrive.controls.lib.drive_helpers import get_steer_max, DT
+from common.numpy_fast import clip
+from cereal import log
+
+
+class LatControlINDI(object):
+ def __init__(self, CP):
+ self.angle_steers_des = 0.
+
+ A = np.matrix([[1.0, DT, 0.0],
+ [0.0, 1.0, DT],
+ [0.0, 0.0, 1.0]])
+ C = np.matrix([[1.0, 0.0, 0.0],
+ [0.0, 1.0, 0.0]])
+
+ # Q = np.matrix([[1e-2, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 10.0]])
+ # R = np.matrix([[1e-2, 0.0], [0.0, 1e3]])
+
+ # (x, l, K) = control.dare(np.transpose(A), np.transpose(C), Q, R)
+ # K = np.transpose(K)
+ K = np.matrix([[7.30262179e-01, 2.07003658e-04],
+ [7.29394177e+00, 1.39159419e-02],
+ [1.71022442e+01, 3.38495381e-02]])
+
+ self.K = K
+ self.A_K = A - np.dot(K, C)
+ self.x = np.matrix([[0.], [0.], [0.]])
+
+ self.enfore_rate_limit = CP.carName == "toyota"
+
+ self.RC = CP.lateralTuning.indi.timeConstant
+ self.G = CP.lateralTuning.indi.actuatorEffectiveness
+ self.outer_loop_gain = CP.lateralTuning.indi.outerLoopGain
+ self.inner_loop_gain = CP.lateralTuning.indi.innerLoopGain
+ self.alpha = 1. - DT / (self.RC + DT)
+
+ self.reset()
+
+ def reset(self):
+ self.delayed_output = 0.
+ self.output_steer = 0.
+ self.counter = 0
+
+ def update(self, active, v_ego, angle_steers, angle_steers_rate, steer_override, CP, VM, path_plan):
+ # Update Kalman filter
+ y = np.matrix([[math.radians(angle_steers)], [math.radians(angle_steers_rate)]])
+ self.x = np.dot(self.A_K, self.x) + np.dot(self.K, y)
+
+ indi_log = log.Live100Data.LateralINDIState.new_message()
+ indi_log.steerAngle = math.degrees(self.x[0])
+ indi_log.steerRate = math.degrees(self.x[1])
+ indi_log.steerAccel = math.degrees(self.x[2])
+
+ if v_ego < 0.3 or not active:
+ indi_log.active = False
+ self.output_steer = 0.0
+ self.delayed_output = 0.0
+ else:
+ self.angle_steers_des = path_plan.angleSteers
+ self.rate_steers_des = path_plan.rateSteers
+
+ steers_des = math.radians(self.angle_steers_des)
+ rate_des = math.radians(self.rate_steers_des)
+
+ # Expected actuator value
+ self.delayed_output = self.delayed_output * self.alpha + self.output_steer * (1. - self.alpha)
+
+ # Compute acceleration error
+ rate_sp = self.outer_loop_gain * (steers_des - self.x[0]) + rate_des
+ accel_sp = self.inner_loop_gain * (rate_sp - self.x[1])
+ accel_error = accel_sp - self.x[2]
+
+ # Compute change in actuator
+ g_inv = 1. / self.G
+ delta_u = g_inv * accel_error
+
+ # Enforce rate limit
+ if self.enfore_rate_limit:
+ steer_max = float(SteerLimitParams.STEER_MAX)
+ new_output_steer_cmd = steer_max * (self.delayed_output + delta_u)
+ prev_output_steer_cmd = steer_max * self.output_steer
+ new_output_steer_cmd = apply_toyota_steer_torque_limits(new_output_steer_cmd, prev_output_steer_cmd, prev_output_steer_cmd, SteerLimitParams)
+ self.output_steer = new_output_steer_cmd / steer_max
+ else:
+ self.output_steer = self.delayed_output + delta_u
+
+ steers_max = get_steer_max(CP, v_ego)
+ self.output_steer = clip(self.output_steer, -steers_max, steers_max)
+
+ indi_log.active = True
+ indi_log.rateSetPoint = float(rate_sp)
+ indi_log.accelSetPoint = float(accel_sp)
+ indi_log.accelError = float(accel_error)
+ indi_log.delayedOutput = float(self.delayed_output)
+ indi_log.delta = float(delta_u)
+ indi_log.output = float(self.output_steer)
+
+ self.sat_flag = False
+ return float(self.output_steer), float(self.angle_steers_des), indi_log
diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol_pid.py
similarity index 63%
rename from selfdrive/controls/lib/latcontrol.py
rename to selfdrive/controls/lib/latcontrol_pid.py
index 6949438708..600990aaa3 100644
--- a/selfdrive/controls/lib/latcontrol.py
+++ b/selfdrive/controls/lib/latcontrol_pid.py
@@ -1,29 +1,27 @@
from selfdrive.controls.lib.pid import PIController
-from common.numpy_fast import interp
+from selfdrive.controls.lib.drive_helpers import get_steer_max
from cereal import car
+from cereal import log
-_DT = 0.01 # 100Hz
-_DT_MPC = 0.05 # 20Hz
-
-def get_steer_max(CP, v_ego):
- return interp(v_ego, CP.steerMaxBP, CP.steerMaxV)
-
-
-class LatControl(object):
+class LatControlPID(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.pid = PIController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV),
+ (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV),
+ k_f=CP.lateralTuning.pid.kf, pos_limit=1.0)
self.angle_steers_des = 0.
def reset(self):
self.pid.reset()
- def update(self, active, v_ego, angle_steers, steer_override, CP, VM, path_plan):
+ def update(self, active, v_ego, angle_steers, angle_steers_rate, steer_override, CP, VM, path_plan):
+ pid_log = log.Live100Data.LateralPIDState.new_message()
+ pid_log.steerAngle = float(angle_steers)
+ pid_log.steerRate = float(angle_steers_rate)
+
if v_ego < 0.3 or not active:
output_steer = 0.0
+ pid_log.active = False
self.pid.reset()
else:
# TODO: ideally we should interp, but for tuning reasons we keep the mpc solution
@@ -43,6 +41,12 @@ class LatControl(object):
deadzone = 0.0
output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override,
feedforward=steer_feedforward, speed=v_ego, deadzone=deadzone)
+ pid_log.active = True
+ pid_log.p = self.pid.p
+ pid_log.i = self.pid.i
+ pid_log.f = self.pid.f
+ pid_log.output = output_steer
+ pid_log.saturated = bool(self.pid.saturated)
self.sat_flag = self.pid.saturated
- return output_steer, float(self.angle_steers_des)
+ return output_steer, float(self.angle_steers_des), pid_log
diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py
index da324a39a1..0b1eefea77 100644
--- a/selfdrive/controls/lib/longcontrol.py
+++ b/selfdrive/controls/lib/longcontrol.py
@@ -58,8 +58,8 @@ def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid,
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),
+ self.pid = PIController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV),
+ (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV),
rate=RATE,
sat_limit=0.8,
convert=compute_gb)
@@ -99,7 +99,7 @@ class LongControl(object):
# 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)
+ deadzone = interp(v_ego_pid, CP.longitudinalTuning.deadzoneBP, CP.longitudinalTuning.deadzoneV)
output_gb = self.pid.update(self.v_pid, v_ego_pid, speed=v_ego_pid, deadzone=deadzone, feedforward=a_target, freeze_integrator=prevent_overshoot)
diff --git a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
index 1f0e28d005..a34fbc3510 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
+++ b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp
@@ -32,7 +32,7 @@ int main( )
// Running cost
Function h;
- h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l));
+ h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - 1;
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);
@@ -42,7 +42,7 @@ int main( )
// Terminal cost
Function hN;
- hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l));
+ hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - 1;
hN << (d_l - desired) / (0.05 * v_ego + 0.5);
hN << a_ego * (0.1 * v_ego + 1.0);
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
index bf64887f19..c0eb83bced 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h
+++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h
@@ -181,8 +181,8 @@ real_t evGx[ 180 ];
/** Column vector of size: 60 */
real_t evGu[ 60 ];
-/** Column vector of size: 15 */
-real_t objAuxVar[ 15 ];
+/** Column vector of size: 13 */
+real_t objAuxVar[ 13 ];
/** Row vector of size: 6 */
real_t objValueIn[ 6 ];
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
index 2129357692..897e0e0fbd 100644
Binary files a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o 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
index e4bf392f98..8cfc06f3b8 100644
--- a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c
+++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c
@@ -73,7 +73,7 @@ void acado_evaluateLSQ(const real_t* in, real_t* out)
const real_t* xd = in;
const real_t* u = in + 3;
const real_t* od = in + 4;
-/* Vector of auxiliary variables; number of elements: 15. */
+/* Vector of auxiliary variables; number of elements: 13. */
real_t* a = acadoWorkspace.objAuxVar;
/* Compute intermediate quantities: */
@@ -87,22 +87,20 @@ a[6] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01))));
a[7] = (a[6]*(real_t)(5.0000000000000000e-01));
a[8] = (a[2]*a[2]);
a[9] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[5]))*a[2])-((((((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(od[0]-xd[0]))*a[7])*a[8])))*a[3]);
-a[10] = (real_t)(0.0000000000000000e+00);
-a[11] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
-a[12] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
-a[13] = (a[11]*a[11]);
-a[14] = (real_t)(0.0000000000000000e+00);
+a[10] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
+a[11] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
+a[12] = (a[10]*a[10]);
/* Compute outputs: */
-out[0] = a[1];
+out[0] = (a[1]-(real_t)(1.0000000000000000e+00));
out[1] = (((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(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[4];
out[5] = a[9];
-out[6] = a[10];
-out[7] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]);
-out[8] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[12])))*a[11])-((((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[13]));
+out[6] = (real_t)(0.0000000000000000e+00);
+out[7] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[10]);
+out[8] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[11])))*a[10])-((((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[12]));
out[9] = (real_t)(0.0000000000000000e+00);
out[10] = (real_t)(0.0000000000000000e+00);
out[11] = (xd[2]*(real_t)(1.0000000000000001e-01));
@@ -110,7 +108,7 @@ out[12] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e
out[13] = (real_t)(0.0000000000000000e+00);
out[14] = (u[0]*(real_t)(1.0000000000000001e-01));
out[15] = (real_t)(0.0000000000000000e+00);
-out[16] = a[14];
+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)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00));
@@ -120,7 +118,7 @@ void acado_evaluateLSQEndTerm(const real_t* in, real_t* out)
{
const real_t* xd = in;
const real_t* od = in + 3;
-/* Vector of auxiliary variables; number of elements: 14. */
+/* Vector of auxiliary variables; number of elements: 13. */
real_t* a = acadoWorkspace.objAuxVar;
/* Compute intermediate quantities: */
@@ -134,20 +132,19 @@ a[6] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01))));
a[7] = (a[6]*(real_t)(5.0000000000000000e-01));
a[8] = (a[2]*a[2]);
a[9] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[5]))*a[2])-((((((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(od[0]-xd[0]))*a[7])*a[8])))*a[3]);
-a[10] = (real_t)(0.0000000000000000e+00);
-a[11] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
-a[12] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
-a[13] = (a[11]*a[11]);
+a[10] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01)));
+a[11] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01));
+a[12] = (a[10]*a[10]);
/* Compute outputs: */
-out[0] = a[1];
+out[0] = (a[1]-(real_t)(1.0000000000000000e+00));
out[1] = (((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(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[4];
out[4] = a[9];
-out[5] = a[10];
-out[6] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]);
-out[7] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[12])))*a[11])-((((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[13]));
+out[5] = (real_t)(0.0000000000000000e+00);
+out[6] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[10]);
+out[7] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(1.8000000000000000e+00)-((real_t)(-1.8000000000000000e+00)))+((xd[1]+xd[1])*a[11])))*a[10])-((((od[0]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(1.8000000000000000e+00))-((od[1]-xd[1])*(real_t)(1.8000000000000000e+00)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((od[1]*od[1])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[12]));
out[8] = (real_t)(0.0000000000000000e+00);
out[9] = (real_t)(0.0000000000000000e+00);
out[10] = (xd[2]*(real_t)(1.0000000000000001e-01));
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
index 435fd9f838..bcdc5b9e81 100644
Binary files a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o differ
diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so
index 3e05e166d6..30f7be05ac 100755
Binary files a/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so and b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so differ
diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o
index 3c0660d96d..f10c23217a 100644
Binary files a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o 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
index 40628ad09f..5a0330ff21 100644
--- a/selfdrive/controls/lib/pathplanner.py
+++ b/selfdrive/controls/lib/pathplanner.py
@@ -49,7 +49,7 @@ class PathPlanner(object):
self.angle_steers_des_prev = 0.0
self.angle_steers_des_time = 0.0
- def update(self, CP, VM, CS, md, live100, live_parameters):
+ def update(self, rcv_times, CP, VM, CS, md, live100, live_parameters):
v_ego = CS.carState.vEgo
angle_steers = CS.carState.steeringAngle
active = live100.live100.active
@@ -104,6 +104,8 @@ class PathPlanner(object):
else:
self.invalid_counter = 0
+ cur_time = sec_since_boot()
+ model_dead = cur_time - rcv_times['model'] > 0.5
plan_valid = self.invalid_counter < 2
plan_send = messaging.new_message()
@@ -121,6 +123,7 @@ class PathPlanner(object):
plan_send.pathPlan.angleOffset = float(angle_offset_average)
plan_send.pathPlan.valid = bool(plan_valid)
plan_send.pathPlan.paramsValid = bool(live_parameters.liveParameters.valid)
+ plan_send.pathPlan.modelValid = bool(not model_dead)
self.plan.send(plan_send.to_bytes())
diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py
index 1d5b32c8fb..f4b2bf88c6 100755
--- a/selfdrive/controls/lib/planner.py
+++ b/selfdrive/controls/lib/planner.py
@@ -6,10 +6,11 @@ from common.params import Params
from common.numpy_fast import interp
import selfdrive.messaging as messaging
+from cereal import car
+from common.realtime import sec_since_boot
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, EventTypes as ET
from selfdrive.controls.lib.speed_smoother import speed_smoother
from selfdrive.controls.lib.longcontrol import LongCtrlState, MIN_CAN_SPEED
from selfdrive.controls.lib.fcw import FCWChecker
@@ -113,9 +114,9 @@ class Planner(object):
self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint])
- def update(self, CS, CP, VM, PP, live20, live100, md, live_map_data):
+ def update(self, rcv_times, CS, CP, VM, PP, live20, live100, md, live_map_data):
"""Gets called when new live20 is available"""
- cur_time = live20.logMonoTime / 1e9
+ cur_time = sec_since_boot()
v_ego = CS.carState.vEgo
long_control_state = live100.live100.longControlState
@@ -131,11 +132,13 @@ class Planner(object):
v_speedlimit = NO_CURVATURE_SPEED
v_curvature = NO_CURVATURE_SPEED
- map_valid = live_map_data.liveMapData.mapValid
+
+ map_age = cur_time - rcv_times['liveMapData']
+ map_valid = live_map_data.liveMapData.mapValid and map_age < 10.0
# Speed limit and curvature
set_speed_limit_active = self.params.get("LimitSetSpeed") == "1" and self.params.get("SpeedLimitOffset") is not None
- if set_speed_limit_active:
+ if set_speed_limit_active and map_valid:
if live_map_data.liveMapData.speedLimitValid:
speed_limit = live_map_data.liveMapData.speedLimit
offset = float(self.params.get("SpeedLimitOffset"))
@@ -206,24 +209,16 @@ class Planner(object):
if fcw:
cloudlog.info("FCW triggered %s", self.fcw_checker.counters)
- model_dead = cur_time - (md.logMonoTime / 1e9) > 0.5
+ radar_dead = cur_time - rcv_times['live20'] > 0.5
+
+ radar_errors = list(live20.live20.radarErrors)
+ radar_fault = car.RadarState.Error.fault in radar_errors
+ radar_comm_issue = car.RadarState.Error.commIssue in radar_errors
# **** send the plan ****
plan_send = messaging.new_message()
plan_send.init('plan')
- # TODO: Move all these events to controlsd. This has nothing to do with planning
- events = []
- if model_dead:
- events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
-
- radar_errors = list(live20.live20.radarErrors)
- if 'commIssue' in radar_errors:
- events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
- if 'fault' in radar_errors:
- events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE]))
-
- plan_send.plan.events = events
plan_send.plan.mdMonoTime = md.logMonoTime
plan_send.plan.l20MonoTime = live20.logMonoTime
@@ -242,6 +237,12 @@ class Planner(object):
plan_send.plan.decelForTurn = decel_for_turn
plan_send.plan.mapValid = map_valid
+ radar_valid = not (radar_dead or radar_fault)
+ plan_send.plan.radarValid = bool(radar_valid)
+ plan_send.plan.radarCommIssue = bool(radar_comm_issue)
+
+ plan_send.plan.processingDelay = (plan_send.logMonoTime / 1e9) - rcv_times['live20']
+
# Send out fcw
fcw = fcw and (self.fcw_enabled or long_control_state != LongCtrlState.off)
plan_send.plan.fcw = fcw
diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py
index da7d3f71ba..99f34dfd5c 100644
--- a/selfdrive/controls/lib/radar_helpers.py
+++ b/selfdrive/controls/lib/radar_helpers.py
@@ -27,7 +27,7 @@ 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_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]])
diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py
index 2a95375408..5946f6192e 100755
--- a/selfdrive/controls/plannerd.py
+++ b/selfdrive/controls/plannerd.py
@@ -1,8 +1,10 @@
#!/usr/bin/env python
import zmq
+from collections import defaultdict
from cereal import car
from common.params import Params
+from common.realtime import sec_since_boot
from selfdrive.swaglog import cloudlog
from selfdrive.services import service_list
from selfdrive.controls.lib.planner import Planner
@@ -52,22 +54,27 @@ def plannerd_thread():
live_parameters.liveParameters.steerRatio = CP.steerRatio
live_parameters.liveParameters.stiffnessFactor = 1.0
+ rcv_times = defaultdict(int)
+
while True:
for socket, event in poller.poll():
+ msg = messaging.recv_one(socket)
+ rcv_times[msg.which()] = sec_since_boot()
+
if socket is live100_sock:
- live100 = messaging.recv_one(socket)
+ live100 = msg
elif socket is car_state_sock:
- car_state = messaging.recv_one(socket)
+ car_state = msg
elif socket is live_parameters_sock:
- live_parameters = messaging.recv_one(socket)
+ live_parameters = msg
elif socket is model_sock:
- model = messaging.recv_one(socket)
- PP.update(CP, VM, car_state, model, live100, live_parameters)
+ model = msg
+ PP.update(rcv_times, CP, VM, car_state, model, live100, live_parameters)
elif socket is live_map_data_sock:
- live_map_data = messaging.recv_one(socket)
+ live_map_data = msg
elif socket is live20_sock:
- live20 = messaging.recv_one(socket)
- PL.update(car_state, CP, VM, PP, live20, live100, model, live_map_data)
+ live20 = msg
+ PL.update(rcv_times, car_state, CP, VM, PP, live20, live100, model, live_map_data)
def main(gctx=None):
diff --git a/selfdrive/controls/tests/__init__.py b/selfdrive/controls/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py
new file mode 100644
index 0000000000..a3cb636012
--- /dev/null
+++ b/selfdrive/controls/tests/test_following_distance.py
@@ -0,0 +1,90 @@
+import unittest
+import numpy as np
+
+from cereal import log
+import selfdrive.messaging as messaging
+from selfdrive.config import Conversions as CV
+from selfdrive.controls.lib.planner import calc_cruise_accel_limits
+from selfdrive.controls.lib.speed_smoother import speed_smoother
+from selfdrive.controls.lib.long_mpc import LongitudinalMpc
+
+
+def RW(v_ego, v_l):
+ TR = 1.8
+ G = 9.81
+ return (v_ego * TR - (v_l - v_ego) * TR + v_ego * v_ego / (2 * G) - v_l * v_l / (2 * G))
+
+
+class FakeSocket(object):
+ def send(self, data):
+ assert data
+
+
+def run_following_distance_simulation(v_lead, t_end=200.0):
+ dt = 0.2
+ t = 0.
+
+ x_lead = 200.0
+
+ x_ego = 0.0
+ v_ego = v_lead
+ a_ego = 0.0
+
+ v_cruise_setpoint = v_lead + 10.
+
+ mpc = LongitudinalMpc(1, FakeSocket())
+
+ first = True
+ while t < t_end:
+ # Run cruise control
+ accel_limits = [float(x) for x in calc_cruise_accel_limits(v_ego, False)]
+ jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])]
+ v_cruise, a_cruise = speed_smoother(v_ego, a_ego, v_cruise_setpoint,
+ accel_limits[1], accel_limits[0],
+ jerk_limits[1], jerk_limits[0],
+ dt)
+
+ # Setup CarState
+ CS = messaging.new_message()
+ CS.init('carState')
+ CS.carState.vEgo = v_ego
+ CS.carState.aEgo = a_ego
+
+ # Setup lead packet
+ lead = log.Live20Data.LeadData.new_message()
+ lead.status = True
+ lead.dRel = x_lead - x_ego
+ lead.vLead = v_lead
+ lead.aLeadK = 0.0
+
+ # Run MPC
+ mpc.set_cur_state(v_ego, a_ego)
+ if first: # Make sure MPC is converged on first timestep
+ for _ in range(20):
+ mpc.update(CS, lead, v_cruise_setpoint)
+ mpc.update(CS, lead, v_cruise_setpoint)
+
+ # Choose slowest of two solutions
+ if v_cruise < mpc.v_mpc:
+ v_ego, a_ego = v_cruise, a_cruise
+ else:
+ v_ego, a_ego = mpc.v_mpc, mpc.a_mpc
+
+ # Update state
+ x_lead += v_lead * dt
+ x_ego += v_ego * dt
+ t += dt
+ first = False
+
+ return x_lead - x_ego
+
+
+class TestFollowingDistance(unittest.TestCase):
+ def test_following_distanc(self):
+ for speed_mph in np.linspace(10, 100, num=10):
+ v_lead = float(speed_mph * CV.MPH_TO_MS)
+
+ simulation_steady_state = run_following_distance_simulation(v_lead)
+ correct_steady_state = RW(v_lead, v_lead) + 4.0
+
+ self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=0.1)
diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py
index 48cca99f91..3ba96fd005 100644
--- a/selfdrive/debug/cpu_usage_stat.py
+++ b/selfdrive/debug/cpu_usage_stat.py
@@ -5,6 +5,7 @@ import sys
import numpy as np
import argparse
import re
+from collections import defaultdict
'''
System tools like top/htop can only show current cpu usage values, so I write this script to do statistics jobs.
@@ -27,9 +28,11 @@ PRINT_INTERVAL = 5
SLEEP_INTERVAL = 0.2
monitored_proc_names = [
- 'ubloxd', 'thermald', 'uploader', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd' , 'logmessaged', 'tombstoned',
+ 'ubloxd', 'thermald', 'uploader', 'deleter', 'controlsd', 'plannerd', 'radard', 'mapd', 'loggerd' , 'logmessaged', 'tombstoned',
'logcatd', 'proclogd', 'boardd', 'pandad', './ui', 'calibrationd', 'locationd', 'visiond', 'sensord', 'updated', 'gpsd', 'athena']
+cpu_time_names = ['user', 'system', 'children_user', 'children_system']
+timer = getattr(time, 'monotonic', time.time)
def get_arg_parser():
parser = argparse.ArgumentParser(
@@ -38,8 +41,10 @@ def get_arg_parser():
parser.add_argument("proc_names", nargs="?", default='',
help="Process names to be monitored, comma seperated")
- parser.add_argument("--list_all", nargs="?", type=bool, default=False,
+ parser.add_argument("--list_all", action='store_true',
help="Show all running processes' cmdline")
+ parser.add_argument("--detailed_times", action='store_true',
+ help="show cpu time details (split by user, system, child user, child system)")
return parser
@@ -61,39 +66,54 @@ if __name__ == "__main__":
if matched:
k = ' '.join(p.cmdline())
print('Add monitored proc:', k)
- stats[k] = {'cpu_samples': [], 'avg_cpu': None, 'min': None, 'max': None}
+ stats[k] = {'cpu_samples': defaultdict(list), 'min': defaultdict(lambda: None), 'max': defaultdict(lambda: None),
+ 'avg': defaultdict(lambda: 0.0), 'last_cpu_times': None, 'last_sys_time':None}
+ stats[k]['last_sys_time'] = timer()
+ stats[k]['last_cpu_times'] = p.cpu_times()
monitored_procs.append(p)
i = 0
interval_int = int(PRINT_INTERVAL / SLEEP_INTERVAL)
while True:
for p in monitored_procs:
k = ' '.join(p.cmdline())
- stats[k]['cpu_samples'].append(p.cpu_percent())
+ cur_sys_time = timer()
+ cur_cpu_times = p.cpu_times()
+ cpu_times = np.subtract(cur_cpu_times, stats[k]['last_cpu_times']) / (cur_sys_time - stats[k]['last_sys_time'])
+ stats[k]['last_sys_time'] = cur_sys_time
+ stats[k]['last_cpu_times'] = cur_cpu_times
+ cpu_percent = 0
+ for num, name in enumerate(cpu_time_names):
+ stats[k]['cpu_samples'][name].append(cpu_times[num])
+ cpu_percent += cpu_times[num]
+ stats[k]['cpu_samples']['total'].append(cpu_percent)
time.sleep(SLEEP_INTERVAL)
i += 1
if i % interval_int == 0:
l = []
- avg_cpus = []
for k, stat in stats.items():
if len(stat['cpu_samples']) <= 0:
continue
- avg_cpu = np.array(stat['cpu_samples']).mean()
- c = len(stat['cpu_samples'])
- stat['cpu_samples'] = []
- if not stat['avg_cpu']:
- stat['avg_cpu'] = avg_cpu
- else:
- stat['avg_cpu'] = (stat['avg_cpu'] * (c + i) + avg_cpu * c) / (c + i + c)
- if not stat['min'] or avg_cpu < stat['min']:
- stat['min'] = avg_cpu
- if not stat['max'] or avg_cpu > stat['max']:
- stat['max'] = avg_cpu
- msg = 'avg: {1:.2f}%, min: {2:.2f}%, max: {3:.2f}% {0}'.format(os.path.basename(k), stat['avg_cpu'], stat['min'], stat['max'])
- l.append((os.path.basename(k), avg_cpu, msg))
- avg_cpus.append(avg_cpu)
+ for name, samples in stat['cpu_samples'].iteritems():
+ samples = np.array(samples)
+ avg = samples.mean()
+ c = samples.size
+ min_cpu = np.amin(samples)
+ max_cpu = np.amax(samples)
+ if stat['min'][name] is None or min_cpu < stat['min'][name]:
+ stat['min'][name] = min_cpu
+ if stat['max'][name] is None or max_cpu > stat['max'][name]:
+ stat['max'][name] = max_cpu
+ stat['avg'][name] = (stat['avg'][name] * (i - c) + avg * c) / (i)
+ stat['cpu_samples'][name] = []
+
+ msg = 'avg: {1:.2%}, min: {2:.2%}, max: {3:.2%} {0}'.format(os.path.basename(k), stat['avg']['total'], stat['min']['total'], stat['max']['total'])
+ if args.detailed_times:
+ for stat_type in ['avg', 'min', 'max']:
+ msg += '\n {}: {}'.format(stat_type, [name + ':' + str(round(stat[stat_type][name]*100, 2)) for name in cpu_time_names])
+ l.append((os.path.basename(k), stat['avg']['total'], msg))
l.sort(key= lambda x: -x[1])
for x in l:
print(x[2])
- print('avg sum: {0:.2f}%\n'.format(
- sum([stat['avg_cpu'] for k, stat in stats.items()])
+ print('avg sum: {0:.2%} over {1} samples {2} seconds\n'.format(
+ sum([stat['avg']['total'] for k, stat in stats.items()]), i, i * SLEEP_INTERVAL
))
diff --git a/selfdrive/debug/tuner.py b/selfdrive/debug/tuner.py
new file mode 100755
index 0000000000..066b0841ab
--- /dev/null
+++ b/selfdrive/debug/tuner.py
@@ -0,0 +1,67 @@
+#!/usr/bin/env python
+"""
+This tool can be used to quickly changes the values in a JSON file used for tuning
+Keys like in vim:
+ - h: decrease by 0.05
+ - l: increase by 0.05
+ - k: move pointer up
+ - j: move pointer down
+"""
+
+import tty
+import sys
+import json
+import termios
+from collections import OrderedDict
+
+FILENAME = '/data/tuning.json'
+
+def read_tuning():
+ while True:
+ try:
+ return json.loads(open(FILENAME).read())
+ except:
+ pass
+
+def main():
+ dat = json.loads(open(FILENAME, 'r').read())
+ dat = OrderedDict(sorted(dat.items(), key=lambda i: i[0]))
+
+ cur = 0
+ while True:
+ sys.stdout.write("\x1Bc")
+
+ for i, (k, v) in enumerate(dat.items()):
+ prefix = "> " if cur == i else " "
+ print((prefix + k).ljust(20) + "%.2f" % v)
+
+ key = sys.stdin.read(1)[0]
+
+ write = False
+ if key == "k":
+ cur = max(0, cur - 1)
+ elif key == "j":
+ cur = min(len(dat.keys()) - 1, cur + 1)
+ elif key == "l":
+ dat[dat.keys()[cur]] += 0.05
+ write = True
+ elif key == "h":
+ dat[dat.keys()[cur]] -= 0.05
+ write = True
+ elif key == "q":
+ break
+
+ if write:
+ open(FILENAME, 'w').write(json.dumps(dat))
+
+
+if __name__ == "__main__":
+ orig_settings = termios.tcgetattr(sys.stdin)
+ tty.setcbreak(sys.stdin)
+
+ try:
+ main()
+ termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings)
+ except:
+ termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings)
+ raise
diff --git a/selfdrive/locationd/.gitignore b/selfdrive/locationd/.gitignore
new file mode 100644
index 0000000000..6c8271a885
--- /dev/null
+++ b/selfdrive/locationd/.gitignore
@@ -0,0 +1,2 @@
+ubloxd
+ubloxd_test
diff --git a/selfdrive/locationd/kalman/.gitignore b/selfdrive/locationd/kalman/.gitignore
new file mode 100644
index 0000000000..9d357c72cc
--- /dev/null
+++ b/selfdrive/locationd/kalman/.gitignore
@@ -0,0 +1,4 @@
+lane.cpp
+gnss.cpp
+loc*.cpp
+pos_computer*.cpp
diff --git a/selfdrive/loggerd/deleter.py b/selfdrive/loggerd/deleter.py
new file mode 100644
index 0000000000..01a91d7749
--- /dev/null
+++ b/selfdrive/loggerd/deleter.py
@@ -0,0 +1,39 @@
+#!/usr/bin/env python
+import os
+import shutil
+import threading
+from selfdrive.swaglog import cloudlog
+from selfdrive.loggerd.config import ROOT
+from selfdrive.loggerd.uploader import listdir_by_creation_date
+
+
+def deleter_thread(exit_event):
+ while not exit_event.is_set():
+ statvfs = os.statvfs(ROOT)
+ available_percent = 100.0 * statvfs.f_bavail / statvfs.f_blocks
+
+ if available_percent < 10.0:
+ # remove the earliest directory we can
+ dirs = listdir_by_creation_date(ROOT)
+ for delete_dir in dirs:
+ delete_path = os.path.join(ROOT, delete_dir)
+
+ if any(name.endswith(".lock") for name in os.listdir(delete_path)):
+ continue
+
+ try:
+ cloudlog.info("deleting %s" % delete_path)
+ shutil.rmtree(delete_path)
+ break
+ except OSError:
+ cloudlog.exception("issue deleting %s" % delete_path)
+
+ exit_event.wait(30)
+
+
+def main(gctx=None):
+ deleter_thread(threading.Event())
+
+
+if __name__ == "__main__":
+ main()
diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd
index 788a29b705..110aafbb3d 100755
Binary files a/selfdrive/loggerd/loggerd and b/selfdrive/loggerd/loggerd differ
diff --git a/selfdrive/loggerd/tests/Makefile b/selfdrive/loggerd/tests/Makefile
new file mode 100644
index 0000000000..d05d549170
--- /dev/null
+++ b/selfdrive/loggerd/tests/Makefile
@@ -0,0 +1,35 @@
+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 \
+ -Wno-deprecated-declarations
+
+CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS)
+CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS)
+
+FFMPEG_LIBS = -lavformat \
+ -lavcodec \
+ -lswscale \
+ -lavutil \
+ -lz
+
+OBJS = testraw.o \
+ ../RawLogger.o \
+ ../../common/visionipc.o
+
+testraw: $(OBJS)
+ $(CXX) -fPIC -o '$@' $^ -L/usr/lib $(FFMPEG_LIBS)
+
+%.o: %.cc
+ @echo "[ CXX ] $@"
+ $(CXX) $(CXXFLAGS) \
+ -I../ \
+ -I../../ \
+ -I../../../ \
+ -c -o '$@' '$<'
diff --git a/selfdrive/loggerd/tests/__init__.py b/selfdrive/loggerd/tests/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/selfdrive/loggerd/tests/fill_eon.py b/selfdrive/loggerd/tests/fill_eon.py
new file mode 100755
index 0000000000..2385e3aa5c
--- /dev/null
+++ b/selfdrive/loggerd/tests/fill_eon.py
@@ -0,0 +1,27 @@
+#!/usr/bin/env python
+"""Script to fill up EON with fake data"""
+
+import os
+
+from selfdrive.loggerd.config import ROOT
+from selfdrive.loggerd.tests.loggerd_tests_common import create_random_file
+
+
+if __name__ == "__main__":
+ segment_idx = 0
+ while True:
+ seg_name = "1970-01-01--00-00-00--%d" % segment_idx
+ seg_path = os.path.join(ROOT, seg_name)
+
+ print(seg_path)
+
+ create_random_file(os.path.join(seg_path, 'fcamera.hevc'), 36)
+ create_random_file(os.path.join(seg_path, 'rlog.bz2'), 2)
+
+ segment_idx += 1
+
+ # Fill up to 99 percent
+ statvfs = os.statvfs(ROOT)
+ available_percent = 100.0 * statvfs.f_bavail / statvfs.f_blocks
+ if available_percent < 1.0:
+ break
diff --git a/selfdrive/loggerd/tests/loggerd_tests_common.py b/selfdrive/loggerd/tests/loggerd_tests_common.py
new file mode 100644
index 0000000000..dd48381d8e
--- /dev/null
+++ b/selfdrive/loggerd/tests/loggerd_tests_common.py
@@ -0,0 +1,53 @@
+import os
+import errno
+import shutil
+import random
+import tempfile
+import unittest
+
+import selfdrive.loggerd.uploader as uploader
+
+
+def create_random_file(file_path, size_mb, lock=False):
+ try:
+ os.mkdir(os.path.dirname(file_path))
+ except OSError:
+ pass
+
+ lock_path = file_path + ".lock"
+ os.close(os.open(lock_path, os.O_CREAT | os.O_EXCL))
+
+ chunks = 128
+ chunk_bytes = int(size_mb * 1024 * 1024 / chunks)
+ data = os.urandom(chunk_bytes)
+
+ with open(file_path, 'wb') as f:
+ for _ in range(chunks):
+ f.write(data)
+
+ if not lock:
+ os.remove(lock_path)
+
+
+class UploaderTestCase(unittest.TestCase):
+ f_type = "UNKNOWN"
+
+ def setUp(self):
+ self.root = tempfile.mkdtemp()
+ uploader.ROOT = self.root # Monkey patch root dir
+ self.seg_num = random.randint(1, 300)
+ self.seg_format = "2019-04-18--12-52-54--{}"
+ self.seg_dir = self.seg_format.format(self.seg_num)
+
+ def tearDown(self):
+ try:
+ shutil.rmtree(self.root)
+ except OSError as e:
+ if e.errno != errno.ENOENT:
+ raise
+
+ def make_file_with_data(self, f_dir, fn, size_mb=.1, lock=False):
+ file_path = os.path.join(self.root, f_dir, fn)
+ create_random_file(file_path, size_mb)
+
+ return file_path
diff --git a/selfdrive/loggerd/tests/test_deleter.py b/selfdrive/loggerd/tests/test_deleter.py
new file mode 100644
index 0000000000..d804b6f6ff
--- /dev/null
+++ b/selfdrive/loggerd/tests/test_deleter.py
@@ -0,0 +1,104 @@
+import os
+import time
+import threading
+from collections import namedtuple
+
+import selfdrive.loggerd.deleter as deleter
+from common.timeout import Timeout, TimeoutException
+
+from loggerd_tests_common import UploaderTestCase
+
+Stats = namedtuple("Stats", ['f_bavail', 'f_blocks'])
+
+fake_stats = Stats(f_bavail=0, f_blocks=10)
+
+
+def fake_statvfs(d):
+ return fake_stats
+
+
+class TestDeleter(UploaderTestCase):
+ def setUp(self):
+ self.f_type = "fcamera.hevc"
+ super(TestDeleter, self).setUp()
+ deleter.os.statvfs = fake_statvfs
+ deleter.ROOT = self.root
+
+ def tearDown(self):
+ super(TestDeleter, self).tearDown()
+
+ def start_thread(self):
+ self.end_event = threading.Event()
+ self.del_thread = threading.Thread(target=deleter.deleter_thread, args=[self.end_event])
+ self.del_thread.daemon = True
+ self.del_thread.start()
+
+ def join_thread(self):
+ self.end_event.set()
+ self.del_thread.join()
+
+ def test_delete(self):
+ f_path = self.make_file_with_data(self.seg_dir, self.f_type, 1)
+
+ self.start_thread()
+
+ with Timeout(5, "Timeout waiting for file to be deleted"):
+ while os.path.exists(f_path):
+ time.sleep(0.5)
+ self.join_thread()
+
+ self.assertFalse(os.path.exists(f_path), "File not deleted")
+
+ def test_delete_files_in_create_order(self):
+ f_path_1 = self.make_file_with_data(self.seg_dir, self.f_type)
+ time.sleep(1)
+ self.seg_num += 1
+ self.seg_dir = self.seg_format.format(self.seg_num)
+ f_path_2 = self.make_file_with_data(self.seg_dir, self.f_type)
+
+ self.start_thread()
+
+ with Timeout(5, "Timeout waiting for file to be deleted"):
+ while os.path.exists(f_path_1) and os.path.exists(f_path_2):
+ time.sleep(0.5)
+
+ self.join_thread()
+
+ self.assertFalse(os.path.exists(f_path_1), "Older file not deleted")
+
+ self.assertTrue(os.path.exists(f_path_2), "Newer file deleted before older file")
+
+ def test_no_delete_when_available_space(self):
+ global fake_stats
+ f_path = self.make_file_with_data(self.seg_dir, self.f_type)
+
+ fake_stats = Stats(f_bavail=10, f_blocks=10)
+
+ self.start_thread()
+
+ try:
+ with Timeout(2, "Timeout waiting for file to be deleted"):
+ while os.path.exists(f_path):
+ time.sleep(0.5)
+ except TimeoutException:
+ pass
+ finally:
+ self.join_thread()
+
+ self.assertTrue(os.path.exists(f_path), "File deleted with available space")
+
+ def test_no_delete_with_lock_file(self):
+ f_path = self.make_file_with_data(self.seg_dir, self.f_type, lock=True)
+
+ self.start_thread()
+
+ try:
+ with Timeout(2, "Timeout waiting for file to be deleted"):
+ while os.path.exists(f_path):
+ time.sleep(0.5)
+ except TimeoutException:
+ pass
+ finally:
+ self.join_thread()
+
+ self.assertTrue(os.path.exists(f_path), "File deleted when locked")
diff --git a/selfdrive/loggerd/tests/testraw.cc b/selfdrive/loggerd/tests/testraw.cc
new file mode 100644
index 0000000000..80858e6f28
--- /dev/null
+++ b/selfdrive/loggerd/tests/testraw.cc
@@ -0,0 +1,57 @@
+#include
+#include
+#include
+
+#include
+
+#include "common/visionipc.h"
+#include "common/timing.h"
+
+#include "RawLogger.h"
+
+int main() {
+ int err;
+
+ VisionStream stream;
+
+ VisionStreamBufs buf_info;
+ while (true) {
+ err = visionstream_init(&stream, VISION_STREAM_YUV, false, &buf_info);
+ if (err != 0) {
+ printf("visionstream fail\n");
+ usleep(100000);
+ }
+ break;
+ }
+
+ RawLogger vidlogger("prcamera", buf_info.width, buf_info.height, 20);
+ vidlogger.Open("o1");
+
+ for (int cnt=0; cnt<200; cnt++) {
+ VIPCBufExtra extra;
+ VIPSBuf* buf = visionstream_get(&stream, &extra);
+ if (buf == NULL) {
+ printf("visionstream get failed\n");
+ break;
+ }
+
+ if (cnt == 100) {
+ vidlogger.Rotate("o2", 2);
+ }
+
+ uint8_t *y = (uint8_t*)buf->addr;
+ uint8_t *u = y + (buf_info.width*buf_info.height);
+ uint8_t *v = u + (buf_info.width/2)*(buf_info.height/2);
+
+ double t1 = millis_since_boot();
+ vidlogger.LogFrame(cnt, y, u, v, NULL);
+ double t2 = millis_since_boot();
+ printf("%d %.2f\n", cnt, (t2-t1));
+ }
+
+ vidlogger.Close();
+
+ visionstream_destroy(&stream);
+
+ return 0;
+}
diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py
index 670e924ab4..451b0b4120 100644
--- a/selfdrive/loggerd/uploader.py
+++ b/selfdrive/loggerd/uploader.py
@@ -116,7 +116,10 @@ class Uploader(object):
return
for logname in listdir_by_creation_date(self.root):
path = os.path.join(self.root, logname)
- names = os.listdir(path)
+ try:
+ names = os.listdir(path)
+ except OSError:
+ continue
if any(name.endswith(".lock") for name in names):
continue
@@ -194,26 +197,6 @@ class Uploader(object):
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 compress(self, key, fn):
# write out the bz2 compress
if fn.endswith("log"):
@@ -246,7 +229,6 @@ class Uploader(object):
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)
diff --git a/selfdrive/manager.py b/selfdrive/manager.py
index 9c6dd646a7..6dcd982f76 100755
--- a/selfdrive/manager.py
+++ b/selfdrive/manager.py
@@ -42,7 +42,7 @@ def unblock_stdout():
if __name__ == "__main__":
neos_update_required = os.path.isfile("/init.qcom.rc") \
- and (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 8)
+ and (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 9)
if neos_update_required:
# update continue.sh before updating NEOS
if os.path.isfile(os.path.join(BASEDIR, "scripts", "continue.sh")):
@@ -88,6 +88,7 @@ from selfdrive.loggerd.config import ROOT
managed_processes = {
"thermald": "selfdrive.thermald",
"uploader": "selfdrive.loggerd.uploader",
+ "deleter": "selfdrive.loggerd.deleter",
"controlsd": "selfdrive.controls.controlsd",
"plannerd": "selfdrive.controls.plannerd",
"radard": "selfdrive.controls.radard",
@@ -127,6 +128,7 @@ persistent_processes = [
'logcatd',
'tombstoned',
'uploader',
+ 'deleter',
'ui',
'gpsd',
'updated',
diff --git a/selfdrive/mapd/default_speeds_generator.py b/selfdrive/mapd/default_speeds_generator.py
index b03e66d7af..888c9e1df9 100755
--- a/selfdrive/mapd/default_speeds_generator.py
+++ b/selfdrive/mapd/default_speeds_generator.py
@@ -1,6 +1,5 @@
#!/usr/bin/env python
import json
-import six
DEFAULT_OUTPUT_FILENAME = "default_speeds_by_region.json"
@@ -146,6 +145,31 @@ def main(filename = DEFAULT_OUTPUT_FILENAME):
DE.add_rule({"zone:maxspeed": "DE:rural"}, "100")
DE.add_rule({"zone:maxspeed": "DE:motorway"}, "none")
DE.add_rule({"bicycle_road": "yes"}, "30")
+
+
+ """
+ --------------------------------------------------
+ EE - Estonia
+ --------------------------------------------------
+ """
+ EE = Country("EE")
+ countries.append(EE)
+
+ """ Default rules """
+ EE.add_rule({"highway": "motorway"}, "90")
+ EE.add_rule({"highway": "trunk"}, "90")
+ EE.add_rule({"highway": "primary"}, "90")
+ EE.add_rule({"highway": "secondary"}, "50")
+ EE.add_rule({"highway": "tertiary"}, "50")
+ EE.add_rule({"highway": "unclassified"}, "90")
+ EE.add_rule({"highway": "residential"}, "40")
+ EE.add_rule({"highway": "service"}, "40")
+ EE.add_rule({"highway": "motorway_link"}, "90")
+ EE.add_rule({"highway": "trunk_link"}, "70")
+ EE.add_rule({"highway": "primary_link"}, "70")
+ EE.add_rule({"highway": "secondary_link"}, "50")
+ EE.add_rule({"highway": "tertiary_link"}, "50")
+ EE.add_rule({"highway": "living_street"}, "20")
""" --- DO NOT MODIFY CODE BELOW THIS LINE --- """
@@ -206,7 +230,7 @@ class Country(Region):
def jsonify(self):
ret_dict = {}
ret_dict[self.name] = {}
- for r_name, region in six.iteritems(self.regions):
+ for r_name, region in self.regions.items():
ret_dict[self.name].update(region.jsonify())
ret_dict[self.name]['Default'] = self.rules
return ret_dict
diff --git a/selfdrive/mapd/mapd_helpers.py b/selfdrive/mapd/mapd_helpers.py
index 50dde6ecb2..58a33ee41f 100644
--- a/selfdrive/mapd/mapd_helpers.py
+++ b/selfdrive/mapd/mapd_helpers.py
@@ -1,4 +1,3 @@
-import six
import math
import json
import numpy as np
@@ -92,7 +91,7 @@ def geocode_maxspeed(tags, location_info):
rule_valid = all(
tag_name in tags
and tags[tag_name] == value
- for tag_name, value in six.iteritems(rule['tags'])
+ for tag_name, value in rule['tags'].items()
)
if rule_valid:
max_speed = rule['speed']
@@ -103,7 +102,7 @@ def geocode_maxspeed(tags, location_info):
rule_valid = all(
tag_name in tags
and tags[tag_name] == value
- for tag_name, value in six.iteritems(rule['tags'])
+ for tag_name, value in rule['tags'].items()
)
if rule_valid:
max_speed = rule['speed']
diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd
index 72b5570da3..9d1ef14812 100755
Binary files a/selfdrive/sensord/gpsd and b/selfdrive/sensord/gpsd differ
diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord
index b118040cca..67edc76ef4 100755
Binary files a/selfdrive/sensord/sensord and b/selfdrive/sensord/sensord differ
diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py
index ac641e2948..0b86095c56 100755
--- a/selfdrive/test/plant/plant.py
+++ b/selfdrive/test/plant/plant.py
@@ -318,7 +318,7 @@ class Plant(object):
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())
+ Plant.logcan.send(can_list_to_can_capnp(can_msgs))
# ******** 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
diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py
index bacabec299..a2c9b20a8c 100755
--- a/selfdrive/thermald.py
+++ b/selfdrive/thermald.py
@@ -279,10 +279,12 @@ def thermald_thread():
params.car_start()
started_ts = sec_since_boot()
started_seen = True
+ os.system('echo performance > /sys/class/devfreq/soc:qcom,cpubw/governor')
else:
started_ts = None
if off_ts is None:
off_ts = sec_since_boot()
+ os.system('echo powersave > /sys/class/devfreq/soc:qcom,cpubw/governor')
# shutdown if the battery gets lower than 3%, it's discharging, we aren't running for
# more than a minute but we were running
diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py
index 9b90013d10..3d7061c6a6 100644
--- a/selfdrive/tombstoned.py
+++ b/selfdrive/tombstoned.py
@@ -105,7 +105,7 @@ 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})
+ install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}, string_max_length=10000)
client.user_context({'id': os.environ.get('DONGLE_ID')})
while True:
diff --git a/selfdrive/ui/slplay.c b/selfdrive/ui/slplay.c
index 6e5d8b9538..2085057664 100644
--- a/selfdrive/ui/slplay.c
+++ b/selfdrive/ui/slplay.c
@@ -38,25 +38,25 @@ uri_player* slplay_create_player_for_uri(const char* uri, char **error) {
result = (*engineInterface)->CreateAudioPlayer(engineInterface, &player.player, &audioSrc, &audioSnk, 0, NULL, NULL);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to create audio player");
+ *error = "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");
+ *error = "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");
+ *error = "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");
+ *error = "Failed to initialize playstate to SL_PLAYSTATE_PAUSED";
return NULL;
}
@@ -74,29 +74,29 @@ void slplay_setup(char **error) {
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");
+ *error = "Failed to create OpenSL engine";
}
result = (*engine)->Realize(engine, SL_BOOLEAN_FALSE);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to realize OpenSL engine");
+ *error = "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");
+ *error = "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");
+ *error = "Failed to create output mix";
}
result = (*outputMix)->Realize(outputMix, SL_BOOLEAN_FALSE);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to realize output mix");
+ *error = "Failed to realize output mix";
}
}
@@ -120,7 +120,7 @@ void slplay_stop (uri_player* player, char **error) {
result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to set SL_PLAYSTATE_STOPPED");
+ *error = "Failed to set SL_PLAYSTATE_STOPPED";
return;
}
}
@@ -164,7 +164,7 @@ void slplay_play (const char *uri, bool loop, char **error) {
result = (*playInterface)->SetCallbackEventsMask(playInterface, SL_PLAYEVENT_HEADATEND);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to set callback event mask");
+ *error = "Failed to set callback event mask";
return;
}
}
@@ -172,13 +172,13 @@ void slplay_play (const char *uri, bool loop, char **error) {
// Reset the audio player
result = (*playInterface)->ClearMarkerPosition(playInterface);
if (result != SL_RESULT_SUCCESS) {
- *error = strdup("Failed to clear marker position");
+ *error = "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");
+ *error = "Failed to set SL_PLAYSTATE_PLAYING";
}
}
diff --git a/selfdrive/visiond/camera_qcom.c b/selfdrive/visiond/camera_qcom.c
index 08a1dff652..45b782ecf2 100644
--- a/selfdrive/visiond/camera_qcom.c
+++ b/selfdrive/visiond/camera_qcom.c
@@ -1925,6 +1925,8 @@ static void camera_close(CameraState *s) {
LOG("isp release stream: %d", err);
}
}
+
+ free(s->eeprom);
}
diff --git a/selfdrive/visiond/model.cc b/selfdrive/visiond/model.cc
index ef1a7df9f0..2fbb4f3c92 100644
--- a/selfdrive/visiond/model.cc
+++ b/selfdrive/visiond/model.cc
@@ -90,6 +90,7 @@ ModelData model_eval_frame(ModelState* s, cl_command_queue q,
}
void model_free(ModelState* s) {
+ free(s->output);
model_input_free(&s->in);
delete s->m;
}