diff --git a/Jenkinsfile b/Jenkinsfile index aa73ccfc4952c1..f2da8990f81206 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -18,6 +18,18 @@ fi ln -snf ${env.TEST_DIR} /data/pythonpath +if [ -f /EON ]; then + # kill all old procs in the openpilot cpuset + while read p; do + kill "\$p" || true + done < /dev/cpuset/app/tasks + + echo \$\$ > /dev/cpuset/app/tasks || true + + mkdir -p /dev/shm + chmod 777 /dev/shm +fi + cd ${env.TEST_DIR} || true ${cmd} exit 0 @@ -50,15 +62,29 @@ pipeline { } stages { - stage('build release3') { - agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + stage('build releases') { when { branch 'devel-staging' } - steps { - phone_steps("tici", [ - ["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], - ]) + + parallel { + stage('release2') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("eon-build", [ + ["build release2-staging & dashcam-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], + ]) + } + } + + stage('release3') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + steps { + phone_steps("tici", [ + ["build release3-staging & dashcam3-staging", "PUSH=1 $SOURCE_DIR/release/build_release.sh"], + ]) + } + } } } @@ -80,6 +106,41 @@ pipeline { stages { stage('parallel tests') { parallel { + stage('C2: build') { + steps { + phone_steps("eon-build", [ + ["build master-ci", "cd $SOURCE_DIR/release && EXTRA_FILES='tools/' ./build_devel.sh"], + ["build openpilot", "cd selfdrive/manager && ./build.py"], + ["test manager", "python selfdrive/manager/test/test_manager.py"], + ["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"], + ["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"], + ]) + } + } + + stage('C2: replay') { + steps { + phone_steps("eon2", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"], + ]) + } + } + + stage('C2: HW + Unit Tests') { + steps { + phone_steps("eon", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["test sounds", "python selfdrive/ui/tests/test_soundd.py"], + ["test boardd loopback", "python selfdrive/boardd/tests/test_boardd_loopback.py"], + ["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"], + ["test encoder", "python selfdrive/loggerd/tests/test_encoder.py"], + ["test logcatd", "python selfdrive/logcatd/tests/test_logcatd_android.py"], + ["test updater", "python selfdrive/hardware/eon/test_neos_updater.py"], + ]) + } + } + /* stage('Power Consumption Tests') { steps { @@ -101,7 +162,7 @@ pipeline { } */ - stage('build') { + stage('C3: build') { environment { R3_PUSH = "${env.BRANCH_NAME == 'master' ? '1' : ' '}" } @@ -116,7 +177,7 @@ pipeline { } } - stage('HW + Unit Tests') { + stage('C3: HW + Unit Tests') { steps { phone_steps("tici2", [ ["build", "cd selfdrive/manager && ./build.py"], @@ -128,7 +189,17 @@ pipeline { } } - stage('camerad') { + stage('C2: camerad') { + steps { + phone_steps("eon-party", [ + ["build", "cd selfdrive/manager && ./build.py"], + ["test camerad", "python selfdrive/camerad/test/test_camerad.py"], + ["test exposure", "python selfdrive/camerad/test/test_exposure.py"], + ]) + } + } + + stage('C3: camerad') { steps { phone_steps("tici-party", [ ["build", "cd selfdrive/manager && ./build.py"], @@ -138,7 +209,7 @@ pipeline { } } - stage('replay') { + stage('C3: replay') { steps { phone_steps("tici3", [ ["build", "cd selfdrive/manager && ./build.py"], @@ -155,7 +226,7 @@ pipeline { branch 'master' } steps { - phone_steps("tici-build", [ + phone_steps("eon-build", [ ["push devel", "cd $SOURCE_DIR/release && PUSH='master-ci' ./build_devel.sh"], ]) } diff --git a/README.md b/README.md index 5af02de8d9277d..b012883d78428d 100755 --- a/README.md +++ b/README.md @@ -41,8 +41,8 @@ Running in a car To use openpilot in a car, you need four things * This software. It's free and available right here. * One of [the 150+ supported cars](docs/CARS.md). We support Honda, Toyota, Hyundai, Nissan, Kia, Chrysler, Lexus, Acura, Audi, VW, and more. If your car is not supported, but has adaptive cruise control and lane keeping assist, it's likely able to run openpilot. -* A supported device to run this software: a [comma three](https://comma.ai/shop/products/three), or if you like to experiment, a [Ubuntu computer with webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam). -* A way to connect to your car. With a comma three, you need only a [car harness](https://comma.ai/shop/products/car-harness). With a PC, you also need a [black panda](https://comma.ai/shop/products/panda). +* A supported device to run this software. This can be a [comma two](https://comma.ai/shop/products/two), [comma three](https://comma.ai/shop/products/three), or if you like to experiment, a [Ubuntu computer with webcams](https://github.com/commaai/openpilot/tree/master/tools/webcam). +* A way to connect to your car. With a comma two or three, you need only a [car harness](https://comma.ai/shop/products/car-harness). With an EON Gold or PC, you also need a [black panda](https://comma.ai/shop/products/panda). We have detailed instructions for [how to install the device in a car](https://comma.ai/setup). diff --git a/SConstruct b/SConstruct index ec76448235d461..6b520bee413f1f 100644 --- a/SConstruct +++ b/SConstruct @@ -73,9 +73,14 @@ lenv = { rpath = lenv["LD_LIBRARY_PATH"].copy() -if arch == "larch64": +if arch == "aarch64" or arch == "larch64": lenv["LD_LIBRARY_PATH"] += ['/data/data/com.termux/files/usr/lib'] + if arch == "aarch64": + # android + lenv["ANDROID_DATA"] = os.environ['ANDROID_DATA'] + lenv["ANDROID_ROOT"] = os.environ['ANDROID_ROOT'] + cpppath = [ "#third_party/opencl/include", ] @@ -87,17 +92,27 @@ if arch == "larch64": f"#third_party/acados/{arch}/lib", ] - libpath += [ - "#third_party/snpe/larch64", - "#third_party/libyuv/larch64/lib", - "/usr/lib/aarch64-linux-gnu" - ] - cpppath += [ - "#selfdrive/camerad/include", - ] - cflags = ["-DQCOM2", "-mcpu=cortex-a57"] - cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] - rpath += ["/usr/local/lib"] + if arch == "larch64": + libpath += [ + "#third_party/snpe/larch64", + "#third_party/libyuv/larch64/lib", + "/usr/lib/aarch64-linux-gnu" + ] + cpppath += [ + "#selfdrive/camerad/include", + ] + cflags = ["-DQCOM2", "-mcpu=cortex-a57"] + cxxflags = ["-DQCOM2", "-mcpu=cortex-a57"] + rpath += ["/usr/local/lib"] + else: + rpath = [] + libpath += [ + "#third_party/snpe/aarch64", + "#third_party/libyuv/lib", + "/system/vendor/lib64" + ] + cflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"] + cxxflags = ["-DQCOM", "-D_USING_LIBCXX", "-mcpu=cortex-a57"] else: cflags = [] cxxflags = [] @@ -244,7 +259,6 @@ if os.environ.get('SCONS_PROGRESS'): SHARED = False -# TODO: this can probably be removed def abspath(x): if arch == 'aarch64': pth = os.path.join("/data/pythonpath", x[0].path) @@ -273,7 +287,9 @@ Export('envCython') # Qt build environment qt_env = env.Clone() -qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus"] +qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning"] +if arch != "aarch64": + qt_modules += ["DBus"] qt_libs = [] if arch == "Darwin": @@ -288,6 +304,15 @@ if arch == "Darwin": qt_env["LINKFLAGS"] += ["-F" + os.path.join(qt_env['QTDIR'], "lib")] qt_env["FRAMEWORKS"] += [f"Qt{m}" for m in qt_modules] + ["OpenGL"] qt_env.AppendENVPath('PATH', os.path.join(qt_env['QTDIR'], "bin")) +elif arch == "aarch64": + qt_env['QTDIR'] = "/usr" + qt_dirs = [ + f"/usr/include/qt", + ] + qt_dirs += [f"/usr/include/qt/Qt{m}" for m in qt_modules] + + qt_libs = [f"Qt5{m}" for m in qt_modules] + qt_libs += ['EGL', 'GLESv3', 'c++_shared'] else: qt_env['QTDIR'] = "/usr" qt_dirs = [ @@ -365,7 +390,7 @@ rednose_config = { }, } -if arch != "larch64": +if arch not in ["aarch64", "larch64"]: rednose_config['to_build'].update({ 'gnss': ('#selfdrive/locationd/models/gnss_kf.py', True, []), 'loc_4': ('#selfdrive/locationd/models/loc_kf.py', True, []), diff --git a/common/file_helpers.py b/common/file_helpers.py index 8a45fa313c455b..592b2a199a75e5 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -81,12 +81,25 @@ def _get_fileobject(): return writer.get_fileobject(dir=temp_dir) return _get_fileobject +def monkeypatch_os_link(): + # This is neccesary on EON/C2, where os.link is patched out of python + if not hasattr(os, 'link'): + from cffi import FFI + ffi = FFI() + ffi.cdef("int link(const char *oldpath, const char *newpath);") + libc = ffi.dlopen(None) + + def link(src, dest): + return libc.link(src.encode(), dest.encode()) + os.link = link + def atomic_write_on_fs_tmp(path, **kwargs): """Creates an atomic writer using a temporary file in a temporary directory on the same filesystem as path. """ # TODO(mgraczyk): This use of AtomicWriter relies on implementation details to set the temp # directory. + monkeypatch_os_link() writer = AtomicWriter(path, **kwargs) return writer._open(_get_fileobject_func(writer, get_tmpdir_on_same_filesystem(path))) @@ -95,5 +108,6 @@ def atomic_write_in_dir(path, **kwargs): """Creates an atomic writer using a temporary file in the same directory as the destination file. """ + monkeypatch_os_link() writer = AtomicWriter(path, **kwargs) return writer._open(_get_fileobject_func(writer, os.path.dirname(path))) diff --git a/installer/updater/updater b/installer/updater/updater new file mode 100755 index 00000000000000..8bf40708a64510 --- /dev/null +++ b/installer/updater/updater @@ -0,0 +1,2 @@ +#!/usr/bin/bash +echo "this is a compatability shim for old updaters" diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 503ebb5d41662b..ce92895fdb937f 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -8,6 +8,96 @@ source "$BASEDIR/launch_env.sh" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +function two_init { + + # set IO scheduler + setprop sys.io.scheduler noop + for f in /sys/block/*/queue/scheduler; do + echo noop > $f + done + + # *** shield cores 2-3 *** + + # TODO: should we enable this? + # offline cores 2-3 to force recurring timers onto the other cores + #echo 0 > /sys/devices/system/cpu/cpu2/online + #echo 0 > /sys/devices/system/cpu/cpu3/online + #echo 1 > /sys/devices/system/cpu/cpu2/online + #echo 1 > /sys/devices/system/cpu/cpu3/online + + # android gets two cores + echo 0-1 > /dev/cpuset/background/cpus + echo 0-1 > /dev/cpuset/system-background/cpus + echo 0-1 > /dev/cpuset/foreground/cpus + echo 0-1 > /dev/cpuset/foreground/boost/cpus + echo 0-1 > /dev/cpuset/android/cpus + + # openpilot gets all the cores + echo 0-3 > /dev/cpuset/app/cpus + + # mask off 2-3 from RPS and XPS - Receive/Transmit Packet Steering + echo 3 | tee /sys/class/net/*/queues/*/rps_cpus + echo 3 | tee /sys/class/net/*/queues/*/xps_cpus + + # *** set up governors *** + + # +50mW offroad, +500mW onroad for 30% more RAM bandwidth + echo "performance" > /sys/class/devfreq/soc:qcom,cpubw/governor + echo 1056000 > /sys/class/devfreq/soc:qcom,m4m/max_freq + echo "performance" > /sys/class/devfreq/soc:qcom,m4m/governor + + # unclear if these help, but they don't seem to hurt + echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu0/governor + echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu2/governor + + # GPU + echo "performance" > /sys/class/devfreq/b00000.qcom,kgsl-3d0/governor + + # /sys/class/devfreq/soc:qcom,mincpubw is the only one left at "powersave" + # it seems to gain nothing but a wasted 500mW + + # *** set up IRQ affinities *** + + # Collect RIL and other possibly long-running I/O interrupts onto CPU 1 + echo 1 > /proc/irq/78/smp_affinity_list # qcom,smd-modem (LTE radio) + echo 1 > /proc/irq/33/smp_affinity_list # ufshcd (flash storage) + echo 1 > /proc/irq/35/smp_affinity_list # wifi (wlan_pci) + echo 1 > /proc/irq/6/smp_affinity_list # MDSS + + # USB traffic needs realtime handling on cpu 3 + [ -d "/proc/irq/733" ] && echo 3 > /proc/irq/733/smp_affinity_list + + # GPU and camera get cpu 2 + CAM_IRQS="177 178 179 180 181 182 183 184 185 186 192" + for irq in $CAM_IRQS; do + echo 2 > /proc/irq/$irq/smp_affinity_list + done + echo 2 > /proc/irq/193/smp_affinity_list # GPU + + # give GPU threads RT priority + for pid in $(pgrep "kgsl"); do + chrt -f -p 52 $pid + done + + # the flippening! + LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1 + + # disable bluetooth + service call bluetooth_manager 8 + + # wifi scan + wpa_cli IFNAME=wlan0 SCAN + + # Check for NEOS update + if [ $(< /VERSION) != "$REQUIRED_NEOS_VERSION" ]; then + echo "Installing NEOS update" + NEOS_PY="$DIR/selfdrive/hardware/eon/neos.py" + MANIFEST="$DIR/selfdrive/hardware/eon/neos.json" + $NEOS_PY --swap-if-ready $MANIFEST + $DIR/selfdrive/hardware/eon/updater $NEOS_PY $MANIFEST + fi +} + function tici_init { # wait longer for weston to come up if [ -f "$BASEDIR/prebuilt" ]; then @@ -77,7 +167,9 @@ function launch { export PYTHONPATH="$PWD:$PWD/pyextra" # hardware specific init - if [ -f /TICI ]; then + if [ -f /EON ]; then + two_init + elif [ -f /TICI ]; then tici_init fi diff --git a/launch_env.sh b/launch_env.sh index d4b57c909af912..cd0c27f64336b8 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -6,6 +6,10 @@ export NUMEXPR_NUM_THREADS=1 export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 +if [ -z "$REQUIRED_NEOS_VERSION" ]; then + export REQUIRED_NEOS_VERSION="19.1" +fi + if [ -z "$AGNOS_VERSION" ]; then export AGNOS_VERSION="4" fi diff --git a/release/build_release.sh b/release/build_release.sh index 79ab4fb0876982..95fcfea1a1bbac 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -13,6 +13,10 @@ if [ -f /TICI ]; then FILES_SRC="release/files_tici" RELEASE_BRANCH=release3-staging DASHCAM_BRANCH=dashcam3-staging +elif [ -f /EON ]; then + FILES_SRC="release/files_eon" + RELEASE_BRANCH=release2-staging + DASHCAM_BRANCH=dashcam-staging else exit 0 fi diff --git a/release/files_common b/release/files_common index 3c2946c7f6114f..1ba38e49cc4e1e 100644 --- a/release/files_common +++ b/release/files_common @@ -66,6 +66,8 @@ release/* tools/lib/* tools/joystick/* +installer/updater/updater + selfdrive/version.py selfdrive/__init__.py @@ -259,6 +261,14 @@ selfdrive/hardware/__init__.py selfdrive/hardware/base.h selfdrive/hardware/base.py selfdrive/hardware/hw.h +selfdrive/hardware/eon/__init__.py +selfdrive/hardware/eon/androidd.py +selfdrive/hardware/eon/shutdownd.py +selfdrive/hardware/eon/hardware.h +selfdrive/hardware/eon/hardware.py +selfdrive/hardware/eon/neos.py +selfdrive/hardware/eon/neos.json +selfdrive/hardware/eon/updater selfdrive/hardware/tici/__init__.py selfdrive/hardware/tici/hardware.py selfdrive/hardware/tici/amplifier.py @@ -290,6 +300,7 @@ selfdrive/locationd/models/live_kf.cc selfdrive/locationd/calibrationd.py selfdrive/logcatd/SConscript +selfdrive/logcatd/logcatd_android.cc selfdrive/logcatd/logcatd_systemd.cc selfdrive/proclogd/SConscript @@ -321,6 +332,7 @@ selfdrive/loggerd/xattr_cache.py selfdrive/sensord/SConscript selfdrive/sensord/libdiag.h +selfdrive/sensord/sensors_qcom.cc selfdrive/sensord/sensors_qcom2.cc selfdrive/sensord/sensors/*.cc selfdrive/sensord/sensors/*.h @@ -354,6 +366,8 @@ selfdrive/ui/qt/offroad/*.h selfdrive/ui/qt/offroad/*.qml selfdrive/ui/qt/widgets/*.cc selfdrive/ui/qt/widgets/*.h +selfdrive/ui/qt/spinner_aarch64 +selfdrive/ui/qt/text_aarch64 selfdrive/ui/replay/*.cc selfdrive/ui/replay/*.h @@ -365,8 +379,11 @@ selfdrive/camerad/snapshot/* selfdrive/camerad/include/* selfdrive/camerad/cameras/camera_common.h selfdrive/camerad/cameras/camera_common.cc +selfdrive/camerad/cameras/camera_qcom.cc +selfdrive/camerad/cameras/camera_qcom.h selfdrive/camerad/cameras/camera_replay.cc selfdrive/camerad/cameras/camera_replay.h +selfdrive/camerad/cameras/debayer.cl selfdrive/camerad/cameras/sensor_i2c.h selfdrive/camerad/cameras/sensor2_i2c.h @@ -442,6 +459,7 @@ selfdrive/assets/training/* third_party/SConscript +third_party/libgralloc/** third_party/linux/** third_party/opencl/** third_party/zlib/* @@ -462,12 +480,19 @@ third_party/libyuv/lib/** third_party/libyuv/larch64/** third_party/snpe/include/** +third_party/snpe/aarch64** +third_party/snpe/larch64** third_party/snpe/dsp** third_party/acados/x86_64/** +third_party/acados/aarch64/** third_party/acados/larch64/** third_party/acados/include/** +third_party/android_frameworks_native/** +third_party/android_hardware_libhardware/** +third_party/android_system_core/** + scripts/update_now.sh scripts/stop_updater.sh diff --git a/release/files_eon b/release/files_eon new file mode 100644 index 00000000000000..b43bf86b50fd8d --- /dev/null +++ b/release/files_eon @@ -0,0 +1 @@ +README.md diff --git a/release/files_tici b/release/files_tici index f63a750f4de292..59cc41918ff983 100644 --- a/release/files_tici +++ b/release/files_tici @@ -1,5 +1,3 @@ -third_party/snpe/larch64** -third_party/snpe/aarch64-linux-gcc4.9/* third_party/mapbox-gl-native-qt/include/* selfdrive/timezoned.py diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript index bb55c825d48a59..85bc756bc1319c 100644 --- a/selfdrive/camerad/SConscript +++ b/selfdrive/camerad/SConscript @@ -2,7 +2,10 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon] -if arch == "larch64": +if arch == "aarch64": + libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui'] + cameras = ['cameras/camera_qcom.cc'] +elif arch == "larch64": libs += ['atomic'] cameras = ['cameras/camera_qcom2.cc'] else: diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 625c284fa43908..7c4d2748f16c08 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -18,7 +18,10 @@ #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#if QCOM2 +#ifdef QCOM +#include "CL/cl_ext_qcom.h" +#include "selfdrive/camerad/cameras/camera_qcom.h" +#elif QCOM2 #include "CL/cl_ext_qcom.h" #include "selfdrive/camerad/cameras/camera_qcom2.h" #elif WEBCAM @@ -415,6 +418,17 @@ static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { } static ExpRect rect = def_rect; + // use driver face crop for AE + if (Hardware::EON() && sm.updated("driverState")) { + if (auto state = sm["driverState"].getDriverState(); state.getFaceProb() > 0.4) { + auto face_position = state.getFacePosition(); + int x = is_rhd ? 0 : frame_width - (0.5 * frame_height); + x += (face_position[0] * (is_rhd ? -1.0 : 1.0) + 0.5) * (0.5 * frame_height) + x_offset; + int y = (face_position[1] + 0.5) * frame_height + y_offset; + rect = {std::max(0, x - 72), std::min(b->rgb_width - 1, x + 72), 2, + std::max(0, y - 72), std::min(b->rgb_height - 1, y + 72), 1}; + } + } camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); } @@ -438,7 +452,7 @@ void common_process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) void camerad_thread() { cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); -#ifdef QCOM2 +#if defined(QCOM) || defined(QCOM2) const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); #else diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index e415f809821d2a..6fafa0e59dced3 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -29,7 +29,7 @@ #define CAMERA_ID_MAX 10 const int UI_BUF_COUNT = 4; -const int YUV_BUFFER_COUNT = 40; +const int YUV_BUFFER_COUNT = Hardware::EON() ? 100 : 40; enum CameraType { RoadCam = 0, diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc new file mode 100644 index 00000000000000..411ff0aec4ca3b --- /dev/null +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -0,0 +1,1164 @@ +#include "selfdrive/camerad/cameras/camera_qcom.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "selfdrive/camerad/cameras/sensor_i2c.h" +#include "selfdrive/camerad/include/msm_cam_sensor.h" +#include "selfdrive/camerad/include/msmb_camera.h" +#include "selfdrive/camerad/include/msmb_isp.h" +#include "selfdrive/camerad/include/msmb_ispif.h" +#include "selfdrive/common/clutil.h" +#include "selfdrive/common/params.h" +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/timing.h" +#include "selfdrive/common/util.h" + +// leeco actuator (DW9800W H-Bridge Driver IC) +// from sniff +const uint16_t INFINITY_DAC = 364; + +extern ExitHandler do_exit; + +static int cam_ioctl(int fd, unsigned long int request, void *arg, const char *log_msg = nullptr) { + int err = HANDLE_EINTR(ioctl(fd, request, arg)); + if (err != 0 && log_msg) { + LOG(util::string_format("%s: %d", log_msg, err).c_str()); + } + return err; +} +// global var for AE/AF ops +std::atomic road_cam_exp{{0}}; +std::atomic driver_cam_exp{{0}}; + +CameraInfo cameras_supported[CAMERA_ID_MAX] = { + [CAMERA_ID_IMX298] = { + .frame_width = 2328, + .frame_height = 1748, + .frame_stride = 2912, + .bayer = true, + .bayer_flip = 3, + .hdr = true + }, + [CAMERA_ID_OV8865] = { + .frame_width = 1632, + .frame_height = 1224, + .frame_stride = 2040, // seems right + .bayer = true, + .bayer_flip = 3, + .hdr = false + }, + // this exists to get the kernel to build for the LeEco in release + [CAMERA_ID_IMX298_FLIPPED] = { + .frame_width = 2328, + .frame_height = 1748, + .frame_stride = 2912, + .bayer = true, + .bayer_flip = 3, + .hdr = true + }, + [CAMERA_ID_OV10640] = { + .frame_width = 1280, + .frame_height = 1080, + .frame_stride = 2040, + .bayer = true, + .bayer_flip = 0, + .hdr = true + }, +}; + +static void camera_release_buffer(void* cookie, int buf_idx) { + CameraState *s = (CameraState *)cookie; + // printf("camera_release_buffer %d\n", buf_idx); + s->ss[0].qbuf_info[buf_idx].dirty_buf = 1; + HANDLE_EINTR(ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &s->ss[0].qbuf_info[buf_idx])); +} + +int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, msm_camera_i2c_data_type data_type) { + struct msm_camera_i2c_reg_setting out_settings = { + .reg_setting = arr, + .size = (uint16_t)size, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .data_type = data_type, + .delay = 0, + }; + sensorb_cfg_data cfg_data = {.cfgtype = CFG_WRITE_I2C_ARRAY, .cfg.setting = &out_settings}; + return HANDLE_EINTR(ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &cfg_data)); +} + +static int imx298_apply_exposure(CameraState *s, int gain, int integ_lines, uint32_t frame_length) { + int analog_gain = std::min(gain, 448); + s->digital_gain = gain > 448 ? (512.0/(512-(gain))) / 8.0 : 1.0; + //printf("%5d/%5d %5d %f\n", s->cur_integ_lines, s->frame_length, analog_gain, s->digital_gain); + + struct msm_camera_i2c_reg_array reg_array[] = { + // REG_HOLD + {0x104,0x1,0}, + {0x3002,0x0,0}, // long autoexposure off + + // FRM_LENGTH + {0x340, (uint16_t)(frame_length >> 8), 0}, {0x341, (uint16_t)(frame_length & 0xff), 0}, + // INTEG_TIME aka coarse_int_time_addr aka shutter speed + {0x202, (uint16_t)(integ_lines >> 8), 0}, {0x203, (uint16_t)(integ_lines & 0xff),0}, + // global_gain_addr + // if you assume 1x gain is 32, 448 is 14x gain, aka 2^14=16384 + {0x204, (uint16_t)(analog_gain >> 8), 0}, {0x205, (uint16_t)(analog_gain & 0xff),0}, + + // digital gain for colors: gain_greenR, gain_red, gain_blue, gain_greenB + /*{0x20e, digital_gain_gr >> 8, 0}, {0x20f,digital_gain_gr & 0xFF,0}, + {0x210, digital_gain_r >> 8, 0}, {0x211,digital_gain_r & 0xFF,0}, + {0x212, digital_gain_b >> 8, 0}, {0x213,digital_gain_b & 0xFF,0}, + {0x214, digital_gain_gb >> 8, 0}, {0x215,digital_gain_gb & 0xFF,0},*/ + + // REG_HOLD + {0x104,0x0,0}, + }; + return sensor_write_regs(s, reg_array, std::size(reg_array), MSM_CAMERA_I2C_BYTE_DATA); +} + +static int ov8865_apply_exposure(CameraState *s, int gain, int integ_lines, uint32_t frame_length) { + //printf("driver camera: %d %d %d\n", gain, integ_lines, frame_length); + int coarse_gain_bitmap, fine_gain_bitmap; + + // get bitmaps from iso + static const int gains[] = {0, 100, 200, 400, 800}; + int i; + for (i = 1; i < std::size(gains); i++) { + if (gain >= gains[i - 1] && gain < gains[i]) + break; + } + int coarse_gain = i - 1; + float fine_gain = (gain - gains[coarse_gain])/(float)(gains[coarse_gain+1]-gains[coarse_gain]); + coarse_gain_bitmap = (1 << coarse_gain) - 1; + fine_gain_bitmap = ((int)(16*fine_gain) << 3) + 128; // 7th is always 1, 0-2nd are always 0 + + integ_lines *= 16; // The exposure value in reg is in 16ths of a line + + struct msm_camera_i2c_reg_array reg_array[] = { + //{0x104,0x1,0}, + + // FRM_LENGTH + {0x380e, (uint16_t)(frame_length >> 8), 0}, {0x380f, (uint16_t)(frame_length & 0xff), 0}, + // AEC EXPO + {0x3500, (uint16_t)(integ_lines >> 16), 0}, {0x3501, (uint16_t)(integ_lines >> 8), 0}, {0x3502, (uint16_t)(integ_lines & 0xff),0}, + // AEC MANUAL + {0x3503, 0x4, 0}, + // AEC GAIN + {0x3508, (uint16_t)(coarse_gain_bitmap), 0}, {0x3509, (uint16_t)(fine_gain_bitmap), 0}, + + //{0x104,0x0,0}, + }; + return sensor_write_regs(s, reg_array, std::size(reg_array), MSM_CAMERA_I2C_BYTE_DATA); +} + +static void camera_init(VisionIpcServer *v, CameraState *s, int camera_id, int camera_num, + uint32_t pixel_clock, uint32_t line_length_pclk, + uint32_t max_gain, uint32_t fps, cl_device_id device_id, cl_context ctx, + VisionStreamType rgb_type, VisionStreamType yuv_type) { + s->camera_num = camera_num; + s->camera_id = camera_id; + + assert(camera_id < std::size(cameras_supported)); + s->ci = cameras_supported[camera_id]; + assert(s->ci.frame_width != 0); + + s->pixel_clock = pixel_clock; + s->max_gain = max_gain; + s->fps = fps; + s->frame_length = s->pixel_clock / line_length_pclk / s->fps; + s->self_recover = 0; + + s->apply_exposure = (camera_id == CAMERA_ID_IMX298) ? imx298_apply_exposure : ov8865_apply_exposure; + s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type, camera_release_buffer); +} + +void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { + char project_name[1024] = {0}; + property_get("ro.boot.project_name", project_name, ""); + assert(strlen(project_name) == 0); + + // sensor is flipped in LP3 + // IMAGE_ORIENT = 3 + init_array_imx298[0].reg_data = 3; + + // 0 = ISO 100 + // 256 = ISO 200 + // 384 = ISO 400 + // 448 = ISO 800 + // 480 = ISO 1600 + // 496 = ISO 3200 + // 504 = ISO 6400, 8x digital gain + // 508 = ISO 12800, 16x digital gain + // 510 = ISO 25600, 32x digital gain + + camera_init(v, &s->road_cam, CAMERA_ID_IMX298, 0, + /*pixel_clock=*/600000000, /*line_length_pclk=*/5536, + /*max_gain=*/510, //0 (ISO 100)- 448 (ISO 800, max analog gain) - 511 (super noisy) +#ifdef HIGH_FPS + /*fps*/ 60, +#else + /*fps*/ 20, +#endif + device_id, ctx, + VISION_STREAM_RGB_ROAD, VISION_STREAM_ROAD); + + camera_init(v, &s->driver_cam, CAMERA_ID_OV8865, 1, + /*pixel_clock=*/72000000, /*line_length_pclk=*/1602, + /*max_gain=*/510, 10, device_id, ctx, + VISION_STREAM_RGB_DRIVER, VISION_STREAM_DRIVER); + + s->sm = new SubMaster({"driverState"}); + s->pm = new PubMaster({"roadCameraState", "driverCameraState", "thumbnail"}); + + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + // TODO: make lengths correct + s->focus_bufs[i].allocate(0xb80); + s->stats_bufs[i].allocate(0xb80); + } + std::fill_n(s->lapres, std::size(s->lapres), 16160); + s->lap_conv = new LapConv(device_id, ctx, s->road_cam.buf.rgb_width, s->road_cam.buf.rgb_height, s->road_cam.buf.rgb_stride, 3); +} + +static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { + int err = 0; + uint32_t gain = s->cur_gain; + uint32_t integ_lines = s->cur_integ_lines; + + if (exposure_frac >= 0) { + exposure_frac = std::clamp(exposure_frac, 2.0f / s->frame_length, 1.0f); + integ_lines = s->frame_length * exposure_frac; + + // See page 79 of the datasheet, this is the max allowed (-1 for phase adjust) + integ_lines = std::min(integ_lines, s->frame_length - 11); + } + + if (gain_frac >= 0) { + // ISO200 is minimum gain + gain_frac = std::clamp(gain_frac, 1.0f/64, 1.0f); + + // linearize gain response + // TODO: will be wrong for driver camera + // 0.125 -> 448 + // 0.25 -> 480 + // 0.5 -> 496 + // 1.0 -> 504 + // 512 - 512/(128*gain_frac) + gain = (s->max_gain/510) * (512 - 512/(256*gain_frac)); + } + + if (gain != s->cur_gain || integ_lines != s->cur_integ_lines) { + if (s->apply_exposure == ov8865_apply_exposure) { + gain = 800 * gain_frac; // ISO + } + err = s->apply_exposure(s, gain, integ_lines, s->frame_length); + if (err == 0) { + std::lock_guard lk(s->frame_info_lock); + s->cur_gain = gain; + s->cur_integ_lines = integ_lines; + } else { + LOGE("camera %d apply_exposure err: %d", s->camera_num, err); + } + } + + if (err == 0) { + s->cur_exposure_frac = exposure_frac; + std::lock_guard lk(s->frame_info_lock); + s->cur_gain_frac = gain_frac; + } + + //LOGD("set exposure: %f %f - %d", exposure_frac, gain_frac, err); +} + +static void do_autoexposure(CameraState *s, float grey_frac) { + const float target_grey = 0.3; + + s->frame_info_lock.lock(); + s->measured_grey_fraction = grey_frac; + s->target_grey_fraction = target_grey; + s->frame_info_lock.unlock(); + + if (s->apply_exposure == ov8865_apply_exposure) { + // gain limits downstream + const float gain_frac_min = 0.015625; + const float gain_frac_max = 1.0; + // exposure time limits + const uint32_t exposure_time_min = 16; + const uint32_t exposure_time_max = s->frame_length - 11; // copied from set_exposure() + + float cur_gain_frac = s->cur_gain_frac; + float exposure_factor = pow(1.05, (target_grey - grey_frac) / 0.05); + if (cur_gain_frac > 0.125 && exposure_factor < 1) { + cur_gain_frac *= exposure_factor; + } else if (s->cur_integ_lines * exposure_factor <= exposure_time_max && s->cur_integ_lines * exposure_factor >= exposure_time_min) { // adjust exposure time first + s->cur_exposure_frac *= exposure_factor; + } else if (cur_gain_frac * exposure_factor <= gain_frac_max && cur_gain_frac * exposure_factor >= gain_frac_min) { + cur_gain_frac *= exposure_factor; + } + s->frame_info_lock.lock(); + s->cur_gain_frac = cur_gain_frac; + s->frame_info_lock.unlock(); + + set_exposure(s, s->cur_exposure_frac, cur_gain_frac); + } else { // keep the old for others + float new_exposure = s->cur_exposure_frac; + new_exposure *= pow(1.05, (target_grey - grey_frac) / 0.05 ); + //LOGD("diff %f: %f to %f", target_grey - grey_frac, s->cur_exposure_frac, new_exposure); + + float new_gain = s->cur_gain_frac; + if (new_exposure < 0.10) { + new_gain *= 0.95; + } else if (new_exposure > 0.40) { + new_gain *= 1.05; + } + + set_exposure(s, new_exposure, new_gain); + } +} + +static void sensors_init(MultiCameraState *s) { + msm_camera_sensor_slave_info slave_infos[2] = { + (msm_camera_sensor_slave_info){ // road camera + .sensor_name = "imx298", + .eeprom_name = "sony_imx298", + .actuator_name = "dw9800w", + .ois_name = "", + .flash_name = "pmic", + .camera_id = CAMERA_0, + .slave_addr = 32, + .i2c_freq_mode = I2C_FAST_MODE, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .sensor_id_info = {.sensor_id_reg_addr = 22, .sensor_id = 664, .module_id = 9, .vcm_id = 6}, + .power_setting_array = { + .power_setting_a = { + {.seq_type = SENSOR_GPIO, .delay = 1}, + {.seq_type = SENSOR_VREG, .seq_val = 2}, + {.seq_type = SENSOR_GPIO, .seq_val = 5, .config_val = 2}, + {.seq_type = SENSOR_VREG, .seq_val = 1}, + {.seq_type = SENSOR_VREG, .seq_val = 3, .delay = 1}, + {.seq_type = SENSOR_CLK, .config_val = 24000000, .delay = 1}, + {.seq_type = SENSOR_GPIO, .config_val = 2, .delay = 10}, + }, + .size = 7, + .power_down_setting_a = { + {.seq_type = SENSOR_CLK, .delay = 1}, + {.seq_type = SENSOR_GPIO, .delay = 1}, + {.seq_type = SENSOR_VREG, .seq_val = 1}, + {.seq_type = SENSOR_GPIO, .seq_val = 5}, + {.seq_type = SENSOR_VREG, .seq_val = 2}, + {.seq_type = SENSOR_VREG, .seq_val = 3, .delay = 1}, + }, + .size_down = 6, + }, + .is_init_params_valid = 0, + .sensor_init_params = {.modes_supported = 1, .position = BACK_CAMERA_B, .sensor_mount_angle = 90}, + .output_format = MSM_SENSOR_BAYER, + }, + (msm_camera_sensor_slave_info){ // driver camera + .sensor_name = "ov8865_sunny", + .eeprom_name = "ov8865_plus", + .actuator_name = "", + .ois_name = "", + .flash_name = "", + .camera_id = CAMERA_2, + .slave_addr = 108, + .i2c_freq_mode = I2C_FAST_MODE, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .sensor_id_info = {.sensor_id_reg_addr = 12299, .sensor_id = 34917, .module_id = 2}, + .power_setting_array = { + .power_setting_a = { + {.seq_type = SENSOR_GPIO, .delay = 5}, + {.seq_type = SENSOR_VREG, .seq_val = 1}, + {.seq_type = SENSOR_VREG, .seq_val = 2}, + {.seq_type = SENSOR_VREG}, + {.seq_type = SENSOR_CLK, .config_val = 24000000, .delay = 1}, + {.seq_type = SENSOR_GPIO, .config_val = 2, .delay = 1}, + }, + .size = 6, + .power_down_setting_a = { + {.seq_type = SENSOR_GPIO, .delay = 5}, + {.seq_type = SENSOR_CLK, .delay = 1}, + {.seq_type = SENSOR_VREG}, + {.seq_type = SENSOR_VREG, .seq_val = 1}, + {.seq_type = SENSOR_VREG, .seq_val = 2, .delay = 1}, + }, + .size_down = 5, + }, + .is_init_params_valid = 0, + .sensor_init_params = {.modes_supported = 1, .position = FRONT_CAMERA_B, .sensor_mount_angle = 270}, + .output_format = MSM_SENSOR_BAYER, + }}; + + unique_fd sensorinit_fd = open_v4l_by_name_and_index("msm_sensor_init"); + assert(sensorinit_fd >= 0); + for (auto &info : slave_infos) { + info.power_setting_array.power_setting = &info.power_setting_array.power_setting_a[0]; + info.power_setting_array.power_down_setting = &info.power_setting_array.power_down_setting_a[0]; + sensor_init_cfg_data sensor_init_cfg = {.cfgtype = CFG_SINIT_PROBE, .cfg.setting = &info}; + int err = cam_ioctl(sensorinit_fd, VIDIOC_MSM_SENSOR_INIT_CFG, &sensor_init_cfg, "sensor init cfg"); + assert(err >= 0); + } +} + +static void camera_open(CameraState *s, bool is_road_cam) { + struct csid_cfg_data csid_cfg_data = {}; + struct v4l2_event_subscription sub = {}; + + struct msm_actuator_cfg_data actuator_cfg_data = {}; + + // open devices + s->csid_fd = open_v4l_by_name_and_index("msm_csid", is_road_cam ? 0 : 2); + assert(s->csid_fd >= 0); + s->csiphy_fd = open_v4l_by_name_and_index("msm_csiphy", is_road_cam ? 0 : 2); + assert(s->csiphy_fd >= 0); + s->isp_fd = open_v4l_by_name_and_index("vfe", is_road_cam ? 0 : 1); + assert(s->isp_fd >= 0); + + if (is_road_cam) { + s->actuator_fd = open_v4l_by_name_and_index("msm_actuator"); + assert(s->actuator_fd >= 0); + } + + // wait for sensor device + // on first startup, these devices aren't present yet + for (int i = 0; i < 10; i++) { + s->sensor_fd = open_v4l_by_name_and_index(is_road_cam ? "imx298" : "ov8865_sunny"); + if (s->sensor_fd >= 0) break; + LOGW("waiting for sensors..."); + util::sleep_for(1000); // sleep one second + } + assert(s->sensor_fd >= 0); + + // *** SHUTDOWN ALL *** + + // CSIPHY: release csiphy + struct msm_camera_csi_lane_params csi_lane_params = {0}; + csi_lane_params.csi_lane_mask = 0x1f; + csiphy_cfg_data csiphy_cfg_data = { .cfg.csi_lane_params = &csi_lane_params, .cfgtype = CSIPHY_RELEASE}; + int err = cam_ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data, "release csiphy"); + + // CSID: release csid + csid_cfg_data.cfgtype = CSID_RELEASE; + cam_ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data, "release csid"); + + // SENSOR: send power down + struct sensorb_cfg_data sensorb_cfg_data = {.cfgtype = CFG_POWER_DOWN}; + cam_ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data, "sensor power down"); + + // actuator powerdown + actuator_cfg_data.cfgtype = CFG_ACTUATOR_POWERDOWN; + cam_ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data, "actuator powerdown"); + + // reset isp + // struct msm_vfe_axi_halt_cmd halt_cmd = { + // .stop_camif = 1, + // .overflow_detected = 1, + // .blocking_halt = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_HALT, &halt_cmd); + // printf("axi halt: %d\n", err); + + // struct msm_vfe_axi_reset_cmd reset_cmd = { + // .blocking = 1, + // .frame_id = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_RESET, &reset_cmd); + // printf("axi reset: %d\n", err); + + // struct msm_vfe_axi_restart_cmd restart_cmd = { + // .enable_camif = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_RESTART, &restart_cmd); + // printf("axi restart: %d\n", err); + + // **** GO GO GO **** + LOG("******************** GO GO GO ************************"); + + // CSID: init csid + csid_cfg_data.cfgtype = CSID_INIT; + cam_ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data, "init csid"); + + // CSIPHY: init csiphy + csiphy_cfg_data = {.cfgtype = CSIPHY_INIT}; + cam_ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data, "init csiphy"); + + // SENSOR: stop stream + struct msm_camera_i2c_reg_setting stop_settings = { + .reg_setting = stop_reg_array, + .size = std::size(stop_reg_array), + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .data_type = MSM_CAMERA_I2C_BYTE_DATA, + .delay = 0 + }; + sensorb_cfg_data.cfgtype = CFG_SET_STOP_STREAM_SETTING; + sensorb_cfg_data.cfg.setting = &stop_settings; + cam_ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data, "stop stream"); + + // SENSOR: send power up + sensorb_cfg_data = {.cfgtype = CFG_POWER_UP}; + cam_ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data, "sensor power up"); + + // **** configure the sensor **** + + // SENSOR: send i2c configuration + if (s->camera_id == CAMERA_ID_IMX298) { + err = sensor_write_regs(s, init_array_imx298, std::size(init_array_imx298), MSM_CAMERA_I2C_BYTE_DATA); + } else if (s->camera_id == CAMERA_ID_OV8865) { + err = sensor_write_regs(s, init_array_ov8865, std::size(init_array_ov8865), MSM_CAMERA_I2C_BYTE_DATA); + } else { + assert(false); + } + LOG("sensor init i2c: %d", err); + + if (is_road_cam) { + // init the actuator + actuator_cfg_data.cfgtype = CFG_ACTUATOR_POWERUP; + cam_ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data, "actuator powerup"); + + actuator_cfg_data.cfgtype = CFG_ACTUATOR_INIT; + cam_ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data, "actuator init"); + + struct msm_actuator_reg_params_t actuator_reg_params[] = { + { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + // MSB here at address 3 + .reg_addr = 3, + .data_type = 9, + .addr_type = 4, + }, + }; + + struct reg_settings_t actuator_init_settings[] = { + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=1, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, // PD = power down + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=0, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 2 }, // 0 = power up + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=2, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 2 }, // RING = SAC mode + { .reg_addr=6, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=64, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, // 0x40 = SAC3 mode + { .reg_addr=7, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=113, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, + // 0x71 = DIV1 | DIV0 | SACT0 -- Tvib x 1/4 (quarter) + // SAC Tvib = 6.3 ms + 0.1 ms = 6.4 ms / 4 = 1.6 ms + // LSC 1-step = 252 + 1*4 = 256 ms / 4 = 64 ms + }; + + struct region_params_t region_params[] = { + {.step_bound = {238, 0,}, .code_per_step = 235, .qvalue = 128} + }; + + actuator_cfg_data.cfgtype = CFG_SET_ACTUATOR_INFO; + actuator_cfg_data.cfg.set_info = (struct msm_actuator_set_info_t){ + .actuator_params = { + .act_type = ACTUATOR_BIVCM, + .reg_tbl_size = 1, + .data_size = 10, + .init_setting_size = 5, + .i2c_freq_mode = I2C_STANDARD_MODE, + .i2c_addr = 24, + .i2c_addr_type = MSM_ACTUATOR_BYTE_ADDR, + .i2c_data_type = MSM_ACTUATOR_WORD_DATA, + .reg_tbl_params = &actuator_reg_params[0], + .init_settings = &actuator_init_settings[0], + .park_lens = {.damping_step = 1023, .damping_delay = 14000, .hw_params = 11, .max_step = 20}, + }, + .af_tuning_params = { + .initial_code = INFINITY_DAC, + .pwd_step = 0, + .region_size = 1, + .total_steps = 238, + .region_params = ®ion_params[0], + }, + }; + + cam_ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data, "actuator set info"); + } + + if (s->camera_id == CAMERA_ID_IMX298) { + err = sensor_write_regs(s, mode_setting_array_imx298, std::size(mode_setting_array_imx298), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor setup: %d", err); + } + + // CSIPHY: configure csiphy + struct msm_camera_csiphy_params csiphy_params = {}; + if (s->camera_id == CAMERA_ID_IMX298) { + csiphy_params = {.lane_cnt = 4, .settle_cnt = 14, .lane_mask = 0x1f, .csid_core = 0}; + } else if (s->camera_id == CAMERA_ID_OV8865) { + // guess! + csiphy_params = {.lane_cnt = 4, .settle_cnt = 24, .lane_mask = 0x1f, .csid_core = 2}; + } + csiphy_cfg_data.cfgtype = CSIPHY_CFG; + csiphy_cfg_data.cfg.csiphy_params = &csiphy_params; + cam_ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data, "csiphy configure"); + + // CSID: configure csid +#define CSI_STATS 0x35 +#define CSI_PD 0x36 + struct msm_camera_csid_params csid_params = { + .lane_cnt = 4, + .lane_assign = 0x4320, + .phy_sel = (uint8_t)(is_road_cam ? 0 : 2), + .lut_params.num_cid = (uint8_t)(is_road_cam ? 3 : 1), + .lut_params.vc_cfg_a = { + {.cid = 0, .dt = CSI_RAW10, .decode_format = CSI_DECODE_10BIT}, + {.cid = 1, .dt = CSI_PD, .decode_format = CSI_DECODE_10BIT}, + {.cid = 2, .dt = CSI_STATS, .decode_format = CSI_DECODE_10BIT}, + }, + }; + + csid_params.lut_params.vc_cfg[0] = &csid_params.lut_params.vc_cfg_a[0]; + csid_params.lut_params.vc_cfg[1] = &csid_params.lut_params.vc_cfg_a[1]; + csid_params.lut_params.vc_cfg[2] = &csid_params.lut_params.vc_cfg_a[2]; + + csid_cfg_data.cfgtype = CSID_CFG; + csid_cfg_data.cfg.csid_params = &csid_params; + cam_ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data, "csid configure"); + + // ISP: SMMU_ATTACH + msm_vfe_smmu_attach_cmd smmu_attach_cmd = {.security_mode = 0, .iommu_attach_mode = IOMMU_ATTACH}; + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_SMMU_ATTACH, &smmu_attach_cmd, "isp smmu attach"); + + // ******************* STREAM RAW ***************************** + + // configure QMET input + struct msm_vfe_input_cfg input_cfg = {}; + for (int i = 0; i < (is_road_cam ? 3 : 1); i++) { + StreamState *ss = &s->ss[i]; + + memset(&input_cfg, 0, sizeof(struct msm_vfe_input_cfg)); + input_cfg.input_src = (msm_vfe_input_src)(VFE_RAW_0+i); + input_cfg.input_pix_clk = s->pixel_clock; + input_cfg.d.rdi_cfg.cid = i; + input_cfg.d.rdi_cfg.frame_based = 1; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_INPUT_CFG, &input_cfg); + LOG("configure input(%d): %d", i, err); + + // ISP: REQUEST_STREAM + ss->stream_req.axi_stream_handle = 0; + if (is_road_cam) { + ss->stream_req.session_id = 2; + ss->stream_req.stream_id = /*ISP_META_CHANNEL_BIT | */ISP_NATIVE_BUF_BIT | (1+i); + } else { + ss->stream_req.session_id = 3; + ss->stream_req.stream_id = ISP_NATIVE_BUF_BIT | 1; + } + + if (i == 0) { + ss->stream_req.output_format = v4l2_fourcc('R', 'G', '1', '0'); + } else { + ss->stream_req.output_format = v4l2_fourcc('Q', 'M', 'E', 'T'); + } + ss->stream_req.stream_src = (msm_vfe_axi_stream_src)(RDI_INTF_0+i); + +#ifdef HIGH_FPS + if (is_road_cam) { + ss->stream_req.frame_skip_pattern = EVERY_3FRAME; + } +#endif + + ss->stream_req.frame_base = 1; + ss->stream_req.buf_divert = 1; //i == 0; + + // setup stream plane. doesn't even matter? + /*s->stream_req.plane_cfg[0].output_plane_format = Y_PLANE; + s->stream_req.plane_cfg[0].output_width = s->ci.frame_width; + s->stream_req.plane_cfg[0].output_height = s->ci.frame_height; + s->stream_req.plane_cfg[0].output_stride = s->ci.frame_width; + s->stream_req.plane_cfg[0].output_scan_lines = s->ci.frame_height; + s->stream_req.plane_cfg[0].rdi_cid = 0;*/ + + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_REQUEST_STREAM, &ss->stream_req); + LOG("isp request stream: %d -> 0x%x", err, ss->stream_req.axi_stream_handle); + + // ISP: REQUEST_BUF + ss->buf_request.session_id = ss->stream_req.session_id; + ss->buf_request.stream_id = ss->stream_req.stream_id; + ss->buf_request.num_buf = FRAME_BUF_COUNT; + ss->buf_request.buf_type = ISP_PRIVATE_BUF; + ss->buf_request.handle = 0; + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_REQUEST_BUF, &ss->buf_request, "isp request buf"); + LOG("got buf handle: 0x%x", ss->buf_request.handle); + + // ENQUEUE all buffers + for (int j = 0; j < ss->buf_request.num_buf; j++) { + ss->qbuf_info[j].handle = ss->buf_request.handle; + ss->qbuf_info[j].buf_idx = j; + ss->qbuf_info[j].buffer.num_planes = 1; + ss->qbuf_info[j].buffer.planes[0].addr = ss->bufs[j].fd; + ss->qbuf_info[j].buffer.planes[0].length = ss->bufs[j].len; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &ss->qbuf_info[j]); + } + + // ISP: UPDATE_STREAM + struct msm_vfe_axi_stream_update_cmd update_cmd = {}; + update_cmd.num_streams = 1; + update_cmd.update_info[0].user_stream_id = ss->stream_req.stream_id; + update_cmd.update_info[0].stream_handle = ss->stream_req.axi_stream_handle; + update_cmd.update_type = UPDATE_STREAM_ADD_BUFQ; + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_UPDATE_STREAM, &update_cmd, "isp update stream"); + } + + LOG("******** START STREAMS ********"); + + sub.id = 0; + sub.type = 0x1ff; + cam_ioctl(s->isp_fd, VIDIOC_SUBSCRIBE_EVENT, &sub, "isp subscribe"); + + // ISP: START_STREAM + s->stream_cfg.cmd = START_STREAM; + s->stream_cfg.num_streams = is_road_cam ? 3 : 1; + for (int i = 0; i < s->stream_cfg.num_streams; i++) { + s->stream_cfg.stream_handle[i] = s->ss[i].stream_req.axi_stream_handle; + } + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_CFG_STREAM, &s->stream_cfg, "isp start stream"); +} + +static void road_camera_start(CameraState *s) { + set_exposure(s, 1.0, 1.0); + + int err = sensor_write_regs(s, start_reg_array, std::size(start_reg_array), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor start regs: %d", err); + + int inf_step = 512 - INFINITY_DAC; + + // initial guess + s->lens_true_pos = 400; + + // reset lens position + struct msm_actuator_cfg_data actuator_cfg_data = {}; + actuator_cfg_data.cfgtype = CFG_SET_POSITION; + actuator_cfg_data.cfg.setpos = (struct msm_actuator_set_position_t){ + .number_of_steps = 1, + .hw_params = (uint32_t)7, + .pos = {INFINITY_DAC, 0}, + .delay = {0,} + }; + cam_ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data, "actuator set pos"); + + // TODO: confirm this isn't needed + /*memset(&actuator_cfg_data, 0, sizeof(actuator_cfg_data)); + actuator_cfg_data.cfgtype = CFG_MOVE_FOCUS; + actuator_cfg_data.cfg.move = (struct msm_actuator_move_params_t){ + .dir = 0, + .sign_dir = 1, + .dest_step_pos = inf_step, + .num_steps = inf_step, + .curr_lens_pos = 0, + .ringing_params = &actuator_ringing_params, + }; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); // should be ~332 at startup ? + LOG("init actuator move focus: %d", err);*/ + //actuator_cfg_data.cfg.move.curr_lens_pos; + + s->cur_lens_pos = 0; + s->cur_step_pos = inf_step; + + actuator_move(s, s->cur_lens_pos); + LOG("init lens pos: %d", s->cur_lens_pos); +} + +void actuator_move(CameraState *s, uint16_t target) { + // LP3 moves only on even positions. TODO: use proper sensor params + + // focus on infinity assuming phone is perpendicular + static struct damping_params_t actuator_ringing_params = { + .damping_step = 1023, + .damping_delay = 20000, + .hw_params = 13, + }; + + int step = (target - s->cur_lens_pos) / 2; + + int dest_step_pos = s->cur_step_pos + step; + dest_step_pos = std::clamp(dest_step_pos, 0, 255); + + struct msm_actuator_cfg_data actuator_cfg_data = {0}; + actuator_cfg_data.cfgtype = CFG_MOVE_FOCUS; + actuator_cfg_data.cfg.move = (struct msm_actuator_move_params_t){ + .dir = (int8_t)((step > 0) ? MOVE_NEAR : MOVE_FAR), + .sign_dir = (int8_t)((step > 0) ? MSM_ACTUATOR_MOVE_SIGNED_NEAR : MSM_ACTUATOR_MOVE_SIGNED_FAR), + .dest_step_pos = (int16_t)dest_step_pos, + .num_steps = abs(step), + .curr_lens_pos = s->cur_lens_pos, + .ringing_params = &actuator_ringing_params, + }; + HANDLE_EINTR(ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data)); + + s->cur_step_pos = dest_step_pos; + s->cur_lens_pos = actuator_cfg_data.cfg.move.curr_lens_pos; + //LOGD("step %d target: %d lens pos: %d", dest_step_pos, target, s->cur_lens_pos); +} + +static void parse_autofocus(CameraState *s, uint8_t *d) { + int good_count = 0; + int16_t max_focus = -32767; + int avg_focus = 0; + + /*printf("FOCUS: "); + for (int i = 0; i < 0x10; i++) { + printf("%2.2X ", d[i]); + }*/ + + for (int i = 0; i < NUM_FOCUS; i++) { + int doff = i*5+5; + s->confidence[i] = d[doff]; + // this should just be a 10-bit signed int instead of 11 + // TODO: write it in a nicer way + int16_t focus_t = (d[doff+1] << 3) | (d[doff+2] >> 5); + if (focus_t >= 1024) focus_t = -(2048-focus_t); + s->focus[i] = focus_t; + //printf("%x->%d ", d[doff], focus_t); + if (s->confidence[i] > 0x20) { + good_count++; + max_focus = std::max(max_focus, s->focus[i]); + avg_focus += s->focus[i]; + } + } + // self recover override + if (s->self_recover > 1) { + s->focus_err = 200 * ((s->self_recover % 2 == 0) ? 1:-1); // far for even numbers, close for odd + s->self_recover -= 2; + return; + } + + if (good_count < 4) { + s->focus_err = nan(""); + return; + } + + avg_focus /= good_count; + + // outlier rejection + if (abs(avg_focus - max_focus) > 200) { + s->focus_err = nan(""); + return; + } + + s->focus_err = max_focus*1.0; +} + +static void do_autofocus(CameraState *s) { + float lens_true_pos = s->lens_true_pos.load(); + if (!isnan(s->focus_err)) { + // learn lens_true_pos + const float focus_kp = 0.005; + lens_true_pos -= s->focus_err*focus_kp; + } + + // stay off the walls + lens_true_pos = std::clamp(lens_true_pos, float(LP3_AF_DAC_DOWN), float(LP3_AF_DAC_UP)); + s->lens_true_pos.store(lens_true_pos); + actuator_move(s, lens_true_pos); +} + +void camera_autoexposure(CameraState *s, float grey_frac) { + if (s->camera_num == 0) { + CameraExpInfo tmp = road_cam_exp.load(); + tmp.op_id++; + tmp.grey_frac = grey_frac; + road_cam_exp.store(tmp); + } else { + CameraExpInfo tmp = driver_cam_exp.load(); + tmp.op_id++; + tmp.grey_frac = grey_frac; + driver_cam_exp.store(tmp); + } +} + +static void driver_camera_start(CameraState *s) { + set_exposure(s, 1.0, 1.0); + int err = sensor_write_regs(s, start_reg_array, std::size(start_reg_array), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor start regs: %d", err); +} + +void cameras_open(MultiCameraState *s) { + struct msm_ispif_param_data ispif_params = { + .num = 4, + .entries = { + // road camera + {.vfe_intf = VFE0, .intftype = RDI0, .num_cids = 1, .cids[0] = CID0, .csid = CSID0}, + // driver camera + {.vfe_intf = VFE1, .intftype = RDI0, .num_cids = 1, .cids[0] = CID0, .csid = CSID2}, + // road camera (focus) + {.vfe_intf = VFE0, .intftype = RDI1, .num_cids = 1, .cids[0] = CID1, .csid = CSID0}, + // road camera (stats, for AE) + {.vfe_intf = VFE0, .intftype = RDI2, .num_cids = 1, .cids[0] = CID2, .csid = CSID0}, + }, + }; + s->msmcfg_fd = HANDLE_EINTR(open("/dev/media0", O_RDWR | O_NONBLOCK)); + assert(s->msmcfg_fd >= 0); + + sensors_init(s); + + s->v4l_fd = HANDLE_EINTR(open("/dev/video0", O_RDWR | O_NONBLOCK)); + assert(s->v4l_fd >= 0); + + s->ispif_fd = open_v4l_by_name_and_index("msm_ispif"); + assert(s->ispif_fd >= 0); + + // ISPIF: stop + // memset(&ispif_cfg_data, 0, sizeof(ispif_cfg_data)); + // ispif_cfg_data.cfg_type = ISPIF_STOP_FRAME_BOUNDARY; + // ispif_cfg_data.params = ispif_params; + // err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + // LOG("ispif stop: %d", err); + + LOG("*** open driver camera ***"); + s->driver_cam.ss[0].bufs = s->driver_cam.buf.camera_bufs.get(); + camera_open(&s->driver_cam, false); + + LOG("*** open road camera ***"); + s->road_cam.ss[0].bufs = s->road_cam.buf.camera_bufs.get(); + s->road_cam.ss[1].bufs = s->focus_bufs; + s->road_cam.ss[2].bufs = s->stats_bufs; + camera_open(&s->road_cam, true); + + if (getenv("CAMERA_TEST")) { + cameras_close(s); + exit(0); + } + + // ISPIF: set vfe info + struct ispif_cfg_data ispif_cfg_data = {.cfg_type = ISPIF_SET_VFE_INFO, .vfe_info.num_vfe = 2}; + int err = HANDLE_EINTR(ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data)); + LOG("ispif set vfe info: %d", err); + + // ISPIF: setup + ispif_cfg_data = {.cfg_type = ISPIF_INIT, .csid_version = 0x30050000 /* CSID_VERSION_V35*/}; + cam_ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data, "ispif setup"); + + ispif_cfg_data = {.cfg_type = ISPIF_CFG, .params = ispif_params}; + cam_ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data, "ispif cfg"); + + ispif_cfg_data.cfg_type = ISPIF_START_FRAME_BOUNDARY; + cam_ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data, "ispif start_frame_boundary"); + + driver_camera_start(&s->driver_cam); + road_camera_start(&s->road_cam); +} + + +static void camera_close(CameraState *s) { + // ISP: STOP_STREAM + s->stream_cfg.cmd = STOP_STREAM; + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_CFG_STREAM, &s->stream_cfg, "isp stop stream"); + + for (int i = 0; i < 3; i++) { + StreamState *ss = &s->ss[i]; + if (ss->stream_req.axi_stream_handle != 0) { + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_RELEASE_BUF, &ss->buf_request, "isp release buf"); + + struct msm_vfe_axi_stream_release_cmd stream_release = { + .stream_handle = ss->stream_req.axi_stream_handle, + }; + cam_ioctl(s->isp_fd, VIDIOC_MSM_ISP_RELEASE_STREAM, &stream_release, "isp release stream"); + } + } +} + +const char* get_isp_event_name(uint32_t type) { + switch (type) { + case ISP_EVENT_REG_UPDATE: return "ISP_EVENT_REG_UPDATE"; + case ISP_EVENT_EPOCH_0: return "ISP_EVENT_EPOCH_0"; + case ISP_EVENT_EPOCH_1: return "ISP_EVENT_EPOCH_1"; + case ISP_EVENT_START_ACK: return "ISP_EVENT_START_ACK"; + case ISP_EVENT_STOP_ACK: return "ISP_EVENT_STOP_ACK"; + case ISP_EVENT_IRQ_VIOLATION: return "ISP_EVENT_IRQ_VIOLATION"; + case ISP_EVENT_STATS_OVERFLOW: return "ISP_EVENT_STATS_OVERFLOW"; + case ISP_EVENT_ERROR: return "ISP_EVENT_ERROR"; + case ISP_EVENT_SOF: return "ISP_EVENT_SOF"; + case ISP_EVENT_EOF: return "ISP_EVENT_EOF"; + case ISP_EVENT_BUF_DONE: return "ISP_EVENT_BUF_DONE"; + case ISP_EVENT_BUF_DIVERT: return "ISP_EVENT_BUF_DIVERT"; + case ISP_EVENT_STATS_NOTIFY: return "ISP_EVENT_STATS_NOTIFY"; + case ISP_EVENT_COMP_STATS_NOTIFY: return "ISP_EVENT_COMP_STATS_NOTIFY"; + case ISP_EVENT_FE_READ_DONE: return "ISP_EVENT_FE_READ_DONE"; + case ISP_EVENT_IOMMU_P_FAULT: return "ISP_EVENT_IOMMU_P_FAULT"; + case ISP_EVENT_HW_FATAL_ERROR: return "ISP_EVENT_HW_FATAL_ERROR"; + case ISP_EVENT_PING_PONG_MISMATCH: return "ISP_EVENT_PING_PONG_MISMATCH"; + case ISP_EVENT_REG_UPDATE_MISSING: return "ISP_EVENT_REG_UPDATE_MISSING"; + case ISP_EVENT_BUF_FATAL_ERROR: return "ISP_EVENT_BUF_FATAL_ERROR"; + case ISP_EVENT_STREAM_UPDATE_DONE: return "ISP_EVENT_STREAM_UPDATE_DONE"; + default: return "unknown"; + } +} + +static FrameMetadata get_frame_metadata(CameraState *s, uint32_t frame_id) { + std::lock_guard lk(s->frame_info_lock); + for (auto &i : s->frame_metadata) { + if (i.frame_id == frame_id) { + return i; + } + } + // should never happen + return (FrameMetadata){ + .frame_id = (uint32_t)-1, + }; +} + +static void ops_thread(MultiCameraState *s) { + int last_road_cam_op_id = 0; + int last_driver_cam_op_id = 0; + + CameraExpInfo road_cam_op; + CameraExpInfo driver_cam_op; + + util::set_thread_name("camera_settings"); + while(!do_exit) { + road_cam_op = road_cam_exp.load(); + if (road_cam_op.op_id != last_road_cam_op_id) { + do_autoexposure(&s->road_cam, road_cam_op.grey_frac); + do_autofocus(&s->road_cam); + last_road_cam_op_id = road_cam_op.op_id; + } + + driver_cam_op = driver_cam_exp.load(); + if (driver_cam_op.op_id != last_driver_cam_op_id) { + do_autoexposure(&s->driver_cam, driver_cam_op.grey_frac); + last_driver_cam_op_id = driver_cam_op.op_id; + } + + util::sleep_for(50); + } +} + +static void setup_self_recover(CameraState *c, const uint16_t *lapres, size_t lapres_size) { + const float lens_true_pos = c->lens_true_pos.load(); + int self_recover = c->self_recover.load(); + if (self_recover < 2 && (lens_true_pos < (LP3_AF_DAC_DOWN + 1) || lens_true_pos > (LP3_AF_DAC_UP - 1)) && is_blur(lapres, lapres_size)) { + // truly stuck, needs help + if (--self_recover < -FOCUS_RECOVER_PATIENCE) { + LOGD("road camera bad state detected. attempting recovery from %.1f, recover state is %d", lens_true_pos, self_recover); + // parity determined by which end is stuck at + self_recover = FOCUS_RECOVER_STEPS + (lens_true_pos < LP3_AF_DAC_M ? 1 : 0); + } + } else if (self_recover < 2 && (lens_true_pos < (LP3_AF_DAC_M - LP3_AF_DAC_3SIG) || lens_true_pos > (LP3_AF_DAC_M + LP3_AF_DAC_3SIG))) { + // in suboptimal position with high prob, but may still recover by itself + if (--self_recover < -(FOCUS_RECOVER_PATIENCE * 3)) { + self_recover = FOCUS_RECOVER_STEPS / 2 + (lens_true_pos < LP3_AF_DAC_M ? 1 : 0); + } + } else if (self_recover < 0) { + self_recover += 1; // reset if fine + } + c->self_recover.store(self_recover); +} + +// called by processing_thread +void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { + const CameraBuf *b = &c->buf; + const int roi_id = cnt % std::size(s->lapres); // rolling roi + s->lapres[roi_id] = s->lap_conv->Update(b->q, (uint8_t *)b->cur_rgb_buf->addr, roi_id); + setup_self_recover(c, &s->lapres[0], std::size(s->lapres)); + + MessageBuilder msg; + auto framed = msg.initEvent().initRoadCameraState(); + fill_frame_data(framed, b->cur_frame_data); + if (env_send_road) { + framed.setImage(get_frame_image(b)); + } + framed.setFocusVal(s->road_cam.focus); + framed.setFocusConf(s->road_cam.confidence); + framed.setRecoverState(s->road_cam.self_recover); + framed.setSharpnessScore(s->lapres); + framed.setTransform(b->yuv_transform.v); + s->pm->send("roadCameraState", msg); + + if (cnt % 3 == 0) { + const int x = 290, y = 322, width = 560, height = 314; + const int skip = 1; + camera_autoexposure(c, set_exposure_target(b, x, x + width, skip, y, y + height, skip)); + } +} + +void cameras_run(MultiCameraState *s) { + std::vector threads; + threads.push_back(std::thread(ops_thread, s)); + threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); + threads.push_back(start_process_thread(s, &s->driver_cam, common_process_driver_camera)); + + CameraState* cameras[2] = {&s->road_cam, &s->driver_cam}; + + while (!do_exit) { + struct pollfd fds[2] = {{.fd = cameras[0]->isp_fd, .events = POLLPRI}, + {.fd = cameras[1]->isp_fd, .events = POLLPRI}}; + int ret = poll(fds, std::size(fds), 1000); + if (ret < 0) { + if (errno == EINTR || errno == EAGAIN) continue; + LOGE("poll failed (%d - %d)", ret, errno); + break; + } + + // process cameras + for (int i=0; i<2; i++) { + if (!fds[i].revents) continue; + + CameraState *c = cameras[i]; + + struct v4l2_event ev = {}; + ret = HANDLE_EINTR(ioctl(c->isp_fd, VIDIOC_DQEVENT, &ev)); + const msm_isp_event_data *isp_event_data = (const msm_isp_event_data *)ev.u.data; + + if (ev.type == ISP_EVENT_BUF_DIVERT) { + const int buf_idx = isp_event_data->u.buf_done.buf_idx; + const int buffer = (isp_event_data->u.buf_done.stream_id & 0xFFFF) - 1; + if (buffer == 0) { + c->buf.camera_bufs_metadata[buf_idx] = get_frame_metadata(c, isp_event_data->frame_id); + c->buf.queue(buf_idx); + } else { + auto &ss = c->ss[buffer]; + if (buffer == 1) { + parse_autofocus(c, (uint8_t *)(ss.bufs[buf_idx].addr)); + } + ss.qbuf_info[buf_idx].dirty_buf = 1; + HANDLE_EINTR(ioctl(c->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &ss.qbuf_info[buf_idx])); + } + + } else if (ev.type == ISP_EVENT_EOF) { + const uint64_t timestamp = (isp_event_data->mono_timestamp.tv_sec * 1000000000ULL + isp_event_data->mono_timestamp.tv_usec * 1000); + std::lock_guard lk(c->frame_info_lock); + c->frame_metadata[c->frame_metadata_idx] = (FrameMetadata){ + .frame_id = isp_event_data->frame_id, + .timestamp_eof = timestamp, + .frame_length = (uint32_t)c->frame_length, + .integ_lines = (uint32_t)c->cur_integ_lines, + .lens_pos = c->cur_lens_pos, + .lens_err = c->focus_err, + .lens_true_pos = c->lens_true_pos, + .gain = c->cur_gain_frac, + .measured_grey_fraction = c->measured_grey_fraction, + .target_grey_fraction = c->target_grey_fraction, + .high_conversion_gain = false, + }; + c->frame_metadata_idx = (c->frame_metadata_idx + 1) % METADATA_BUF_COUNT; + + } else if (ev.type == ISP_EVENT_ERROR) { + LOGE("ISP_EVENT_ERROR! err type: 0x%08x", isp_event_data->u.error_info.err_type); + } + } + } + + LOG(" ************** STOPPING **************"); + + for (auto &t : threads) t.join(); + + cameras_close(s); +} + +void cameras_close(MultiCameraState *s) { + camera_close(&s->road_cam); + camera_close(&s->driver_cam); + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + s->focus_bufs[i].free(); + s->stats_bufs[i].free(); + } + + delete s->lap_conv; + delete s->sm; + delete s->pm; +} diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h new file mode 100644 index 00000000000000..87bbe4b7e72618 --- /dev/null +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -0,0 +1,106 @@ +#pragma once + +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "cereal/visionipc/visionbuf.h" +#include "selfdrive/camerad/cameras/camera_common.h" +#include "selfdrive/camerad/imgproc/utils.h" +#include "selfdrive/camerad/include/msm_cam_sensor.h" +#include "selfdrive/camerad/include/msmb_camera.h" +#include "selfdrive/camerad/include/msmb_isp.h" +#include "selfdrive/camerad/include/msmb_ispif.h" +#include "selfdrive/common/mat.h" +#include "selfdrive/common/util.h" + +#define FRAME_BUF_COUNT 4 +#define METADATA_BUF_COUNT 4 + +#define NUM_FOCUS 8 + +#define LP3_AF_DAC_DOWN 366 +#define LP3_AF_DAC_UP 634 +#define LP3_AF_DAC_M 440 +#define LP3_AF_DAC_3SIG 52 + +#define FOCUS_RECOVER_PATIENCE 50 // 2.5 seconds of complete blur +#define FOCUS_RECOVER_STEPS 240 // 6 seconds + +typedef struct CameraState CameraState; + +typedef int (*camera_apply_exposure_func)(CameraState *s, int gain, int integ_lines, uint32_t frame_length); + +typedef struct StreamState { + struct msm_isp_buf_request buf_request; + struct msm_vfe_axi_stream_request_cmd stream_req; + struct msm_isp_qbuf_info qbuf_info[FRAME_BUF_COUNT]; + VisionBuf *bufs; +} StreamState; + +typedef struct CameraState { + int camera_num; + int camera_id; + + int fps; + CameraInfo ci; + + unique_fd csid_fd; + unique_fd csiphy_fd; + unique_fd sensor_fd; + unique_fd isp_fd; + + struct msm_vfe_axi_stream_cfg_cmd stream_cfg; + + StreamState ss[3]; + CameraBuf buf; + + std::mutex frame_info_lock; + FrameMetadata frame_metadata[METADATA_BUF_COUNT]; + int frame_metadata_idx; + + // exposure + uint32_t pixel_clock, line_length_pclk; + uint32_t frame_length; + unsigned int max_gain; + float cur_exposure_frac, cur_gain_frac; + int cur_gain, cur_integ_lines; + + float measured_grey_fraction; + float target_grey_fraction; + + std::atomic digital_gain; + camera_apply_exposure_func apply_exposure; + + // rear camera only,used for focusing + unique_fd actuator_fd; + std::atomic focus_err; + std::atomic lens_true_pos; + std::atomic self_recover; // af recovery counter, neg is patience, pos is active + uint16_t cur_step_pos; + uint16_t cur_lens_pos; + int16_t focus[NUM_FOCUS]; + uint8_t confidence[NUM_FOCUS]; +} CameraState; + + +typedef struct MultiCameraState { + unique_fd ispif_fd; + unique_fd msmcfg_fd; + unique_fd v4l_fd; + uint16_t lapres[(ROI_X_MAX-ROI_X_MIN+1)*(ROI_Y_MAX-ROI_Y_MIN+1)]; + + VisionBuf focus_bufs[FRAME_BUF_COUNT]; + VisionBuf stats_bufs[FRAME_BUF_COUNT]; + + CameraState road_cam; + CameraState driver_cam; + + SubMaster *sm; + PubMaster *pm; + LapConv *lap_conv; +} MultiCameraState; + +void actuator_move(CameraState *s, uint16_t target); +int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, int data_type); diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index 58edaedd9bb692..668410d6f7c2ae 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -7,11 +7,11 @@ #include "selfdrive/hardware/hw.h" int main(int argc, char *argv[]) { - if (Hardware::TICI()) { + if (!Hardware::PC()) { int ret; ret = util::set_realtime_priority(53); assert(ret == 0); - ret = util::set_core_affinity({6}); + ret = util::set_core_affinity({Hardware::EON() ? 2 : 6}); assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores } diff --git a/selfdrive/camerad/test/test_camerad.py b/selfdrive/camerad/test/test_camerad.py index c311c17169ac57..ff37ad1f311936 100755 --- a/selfdrive/camerad/test/test_camerad.py +++ b/selfdrive/camerad/test/test_camerad.py @@ -4,9 +4,11 @@ import unittest import cereal.messaging as messaging -from selfdrive.hardware import TICI from selfdrive.test.helpers import with_processes +# only tests for EON and TICI +from selfdrive.hardware import EON, TICI + TEST_TIMESPAN = 30 # random.randint(60, 180) # seconds SKIP_FRAME_TOLERANCE = 0 LAG_FRAME_TOLERANCE = 2 # ms @@ -24,7 +26,7 @@ class TestCamerad(unittest.TestCase): @classmethod def setUpClass(cls): - if not TICI: + if not (EON or TICI): raise unittest.SkipTest @with_processes(['camerad']) diff --git a/selfdrive/camerad/test/test_exposure.py b/selfdrive/camerad/test/test_exposure.py index 31bcc286819f63..6ed69627b50d27 100755 --- a/selfdrive/camerad/test/test_exposure.py +++ b/selfdrive/camerad/test/test_exposure.py @@ -6,7 +6,7 @@ from selfdrive.test.helpers import with_processes from selfdrive.camerad.snapshot.snapshot import get_snapshots -from selfdrive.hardware import TICI +from selfdrive.hardware import EON, TICI TEST_TIME = 45 REPEAT = 5 @@ -14,7 +14,7 @@ class TestCamerad(unittest.TestCase): @classmethod def setUpClass(cls): - if not TICI: + if not (EON or TICI): raise unittest.SkipTest def _numpy_rgb2gray(self, im): diff --git a/selfdrive/clocksd/clocksd.cc b/selfdrive/clocksd/clocksd.cc index a6a92fc058c152..c24ffa41d94763 100644 --- a/selfdrive/clocksd/clocksd.cc +++ b/selfdrive/clocksd/clocksd.cc @@ -21,6 +21,16 @@ ExitHandler do_exit; +#ifdef QCOM +namespace { + int64_t arm_cntpct() { + int64_t v; + asm volatile("mrs %0, cntpct_el0" : "=r"(v)); + return v; + } +} +#endif + int main() { setpriority(PRIO_PROCESS, 0, -13); PubMaster pm({"clocks"}); @@ -55,6 +65,10 @@ int main() { uint64_t monotonic_raw = nanos_monotonic_raw(); uint64_t wall_time = nanos_since_epoch(); +#ifdef QCOM + uint64_t modem_uptime_v = arm_cntpct() / 19200ULL; // 19.2 mhz clock +#endif + MessageBuilder msg; auto clocks = msg.initEvent().initClocks(); @@ -62,6 +76,9 @@ int main() { clocks.setMonotonicNanos(monotonic); clocks.setMonotonicRawNanos(monotonic_raw); clocks.setWallTimeNanos(wall_time); +#ifdef QCOM + clocks.setModemUptimeMillis(modem_uptime_v); +#endif pm.send("clocks", msg); } diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index e53cb7615db8b4..8dfeecbdd7b4b3 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -22,7 +22,9 @@ files = [ 'visionimg.cc', ] -if arch == "larch64": +if arch == "aarch64": + _gpu_libs = ['gui', 'adreno_utils'] +elif arch == "larch64": _gpu_libs = ["GLESv2"] else: _gpu_libs = ["GL"] diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 6b30e605060453..9ebf7d5ff05348 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -32,9 +32,13 @@ namespace tici_dm_crop { const int width = 954; }; -const mat3 fcam_intrinsic_matrix = (mat3){{2648.0, 0.0, 1928.0 / 2, - 0.0, 2648.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; +const mat3 fcam_intrinsic_matrix = + Hardware::EON() ? (mat3){{910., 0., 1164.0 / 2, + 0., 910., 874.0 / 2, + 0., 0., 1.}} + : (mat3){{2648.0, 0.0, 1928.0 / 2, + 0.0, 2648.0, 1208.0 / 2, + 0.0, 0.0, 1.0}}; // tici ecam focal probably wrong? magnification is not consistent across frame // Need to retrain model before this can be changed @@ -43,7 +47,7 @@ const mat3 ecam_intrinsic_matrix = (mat3){{567.0, 0.0, 1928.0 / 2, 0.0, 0.0, 1.0}}; static inline mat3 get_model_yuv_transform(bool bayer = true) { - float db_s = 1.0; + float db_s = Hardware::EON() ? 0.5 : 1.0; // debayering does a 2x downscale on EON const mat3 transform = (mat3){{ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index a6d3816e47a189..34bab1cb5ffafe 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -168,6 +168,7 @@ std::unordered_map keys = { {"ApiCache_Owner", PERSISTENT}, {"Offroad_BadNvme", CLEAR_ON_MANAGER_START}, {"Offroad_CarUnrecognized", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, + {"Offroad_ChargeDisabled", CLEAR_ON_MANAGER_START }, {"Offroad_ConnectivityNeeded", CLEAR_ON_MANAGER_START}, {"Offroad_ConnectivityNeededPrompt", CLEAR_ON_MANAGER_START}, {"Offroad_InvalidTime", CLEAR_ON_MANAGER_START}, diff --git a/selfdrive/common/swaglog.cc b/selfdrive/common/swaglog.cc index 21115da10fa58b..4036df91d5cd01 100644 --- a/selfdrive/common/swaglog.cc +++ b/selfdrive/common/swaglog.cc @@ -50,7 +50,9 @@ class SwaglogState : public LogState { ctx_j["dirty"] = !getenv("CLEAN"); // device type - if (Hardware::TICI()) { + if (Hardware::EON()) { + ctx_j["device"] = "eon"; + } else if (Hardware::TICI()) { ctx_j["device"] = "tici"; } else { ctx_j["device"] = "pc"; diff --git a/selfdrive/common/tests/test_swaglog.cc b/selfdrive/common/tests/test_swaglog.cc index 47c550463826e3..1d00def63d02e5 100644 --- a/selfdrive/common/tests/test_swaglog.cc +++ b/selfdrive/common/tests/test_swaglog.cc @@ -57,7 +57,9 @@ void recv_log(int thread_cnt, int thread_msg_cnt) { REQUIRE(ctx["version"].string_value() == COMMA_VERSION); std::string device = "pc"; - if (Hardware::TICI()) { + if (Hardware::EON()) { + device = "eon"; + } else if (Hardware::TICI()) { device = "tici"; } REQUIRE(ctx["device"].string_value() == device); diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc index b67f0e202d5c38..a98aabc36c4ace 100644 --- a/selfdrive/common/visionimg.cc +++ b/selfdrive/common/visionimg.cc @@ -2,6 +2,54 @@ #include +#ifdef QCOM +#include +#include +#include +#include +#define GL_GLEXT_PROTOTYPES +#include +using namespace android; + +EGLImageTexture::EGLImageTexture(const VisionBuf *buf) { + const int bpp = 3; + assert((buf->len % buf->stride) == 0); + assert((buf->stride % bpp) == 0); + + const int format = HAL_PIXEL_FORMAT_RGB_888; + private_handle = new private_handle_t(buf->fd, buf->len, + private_handle_t::PRIV_FLAGS_USES_ION|private_handle_t::PRIV_FLAGS_FRAMEBUFFER, + 0, format, + buf->stride/bpp, buf->len/buf->stride, + buf->width, buf->height); + + // GraphicBuffer is ref counted by EGLClientBuffer(ANativeWindowBuffer), no need and not possible to release. + GraphicBuffer* gb = new GraphicBuffer(buf->width, buf->height, (PixelFormat)format, + GraphicBuffer::USAGE_HW_TEXTURE, buf->stride/bpp, (private_handle_t*)private_handle, false); + + EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(display != EGL_NO_DISPLAY); + + EGLint img_attrs[] = {EGL_IMAGE_PRESERVED_KHR, EGL_TRUE, EGL_NONE}; + img_khr = eglCreateImageKHR(display, EGL_NO_CONTEXT, + EGL_NATIVE_BUFFER_ANDROID, gb->getNativeBuffer(), img_attrs); + assert(img_khr != EGL_NO_IMAGE_KHR); + + glGenTextures(1, &frame_tex); + glBindTexture(GL_TEXTURE_2D, frame_tex); + glEGLImageTargetTexture2DOES(GL_TEXTURE_2D, img_khr); +} + +EGLImageTexture::~EGLImageTexture() { + glDeleteTextures(1, &frame_tex); + EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(display != EGL_NO_DISPLAY); + eglDestroyImageKHR(display, img_khr); + delete (private_handle_t*)private_handle; +} + +#else // ifdef QCOM + EGLImageTexture::EGLImageTexture(const VisionBuf *buf) { glGenTextures(1, &frame_tex); glBindTexture(GL_TEXTURE_2D, frame_tex); @@ -12,3 +60,4 @@ EGLImageTexture::EGLImageTexture(const VisionBuf *buf) { EGLImageTexture::~EGLImageTexture() { glDeleteTextures(1, &frame_tex); } +#endif // ifdef QCOM diff --git a/selfdrive/common/visionimg.h b/selfdrive/common/visionimg.h index 0cb41a32b8046e..e8917f3bd618ca 100644 --- a/selfdrive/common/visionimg.h +++ b/selfdrive/common/visionimg.h @@ -8,9 +8,20 @@ #include #endif +#ifdef QCOM +#include +#define EGL_EGLEXT_PROTOTYPES +#include +#undef Status +#endif + class EGLImageTexture { public: EGLImageTexture(const VisionBuf *buf); ~EGLImageTexture(); GLuint frame_tex = 0; +#ifdef QCOM + void *private_handle = nullptr; + EGLImageKHR img_khr = 0; +#endif }; diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index ab23af7b88e880..bb9de5ba76a46c 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -26,7 +26,7 @@ from selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from selfdrive.controls.lib.vehicle_model import VehicleModel from selfdrive.locationd.calibrationd import Calibration -from selfdrive.hardware import HARDWARE, TICI +from selfdrive.hardware import HARDWARE, TICI, EON from selfdrive.manager.process_config import managed_processes SOFT_DISABLE_TIME = 3 # seconds @@ -36,8 +36,9 @@ REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ NOSENSOR = "NOSENSOR" in os.environ -IGNORE_PROCESSES = {"uploader", "deleter", "loggerd", "logmessaged", "tombstoned", "statsd", - "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \ +IGNORE_PROCESSES = {"rtshield", "uploader", "deleter", "loggerd", "logmessaged", "tombstoned", + "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad", + "statsd", "shutdownd"} | \ {k for k, v in managed_processes.items() if not v.enabled} ThermalStatus = log.DeviceState.ThermalStatus @@ -219,7 +220,11 @@ def update_events(self, CS): if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) - # Create events for temperature, disk space, and memory + # Create events for battery, temperature, disk space, and memory + if EON and (self.sm['peripheralState'].pandaType != PandaType.uno) and \ + self.sm['deviceState'].batteryPercent < 1 and self.sm['deviceState'].chargingError: + # at zero percent battery, while discharging, OP should not allowed + self.events.add(EventName.lowBattery) if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: @@ -230,7 +235,7 @@ def update_events(self, CS): self.events.add(EventName.lowMemory) # TODO: enable this once loggerd CPU usage is more reasonable - #cpus = list(self.sm['deviceState'].cpuUsagePercent) + #cpus = list(self.sm['deviceState'].cpuUsagePercent)[:(-1 if EON else None)] #if max(cpus, default=0) > 95 and not SIMULATION: # self.events.add(EventName.highCpuUsage) diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/controls/lib/alerts_offroad.json index 2f85ea917ae6b4..4f0ffa794d9dc3 100644 --- a/selfdrive/controls/lib/alerts_offroad.json +++ b/selfdrive/controls/lib/alerts_offroad.json @@ -1,4 +1,8 @@ { + "Offroad_ChargeDisabled": { + "text": "EON charging disabled after car being off for more than 30 hours. Turn ignition on to start charging again.", + "severity": 0 + }, "Offroad_TemperatureTooHigh": { "text": "Device temperature too high. System won't start.", "severity": 1 diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py index aedf61a073eff5..0230255ef983f2 100644 --- a/selfdrive/controls/lib/lane_planner.py +++ b/selfdrive/controls/lib/lane_planner.py @@ -3,7 +3,7 @@ from common.filter_simple import FirstOrderFilter from common.numpy_fast import interp from common.realtime import DT_MDL -from selfdrive.hardware import TICI +from selfdrive.hardware import EON, TICI from selfdrive.swaglog import cloudlog @@ -13,7 +13,9 @@ # the model knows the difference between TICI and EON # so a path offset is not needed PATH_OFFSET = 0.00 -if TICI: +if EON: + CAMERA_OFFSET = -0.06 +elif TICI: CAMERA_OFFSET = 0.04 else: CAMERA_OFFSET = 0.0 diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript index df1e2a2a1ae6a6..76f7fadce7362b 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript +++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript @@ -48,6 +48,7 @@ acados_templates_dir = '#pyextra/acados_template/c_templates_tera' source_list = ['lat_mpc.py', f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', + f'{acados_dir}/aarch64/lib/libacados.so', f'{acados_dir}/x86_64/lib/libacados.so', f'{acados_dir}/larch64/lib/libacados.so', f'{acados_templates_dir}/acados_solver.in.c', diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript index 5a9e69c29781e8..fd0da63a37ba49 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -55,6 +55,7 @@ acados_templates_dir = '#pyextra/acados_template/c_templates_tera' source_list = ['long_mpc.py', f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', + f'{acados_dir}/aarch64/lib/libacados.so', f'{acados_dir}/x86_64/lib/libacados.so', f'{acados_dir}/larch64/lib/libacados.so', f'{acados_templates_dir}/acados_solver.in.c', diff --git a/selfdrive/debug/README.md b/selfdrive/debug/README.md index f6903170a284ea..d49db25d0920ef 100644 --- a/selfdrive/debug/README.md +++ b/selfdrive/debug/README.md @@ -52,7 +52,7 @@ optional arguments: -h, --help show this help message and exit --debug enable ISO-TP/UDS stack debugging output -This tool is meant to run directly on a vehicle-installed comma three, with +This tool is meant to run directly on a vehicle-installed comma two or comma three, with the openpilot/tmux processes stopped. It should also work on a separate PC with a USB- attached comma panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must turn ignition off and on again for any changes to take effect. diff --git a/selfdrive/debug/adb.sh b/selfdrive/debug/adb.sh index 919a82fefc726b..8a04d4aefd583d 100755 --- a/selfdrive/debug/adb.sh +++ b/selfdrive/debug/adb.sh @@ -4,7 +4,12 @@ set -e PORT=5555 setprop service.adb.tcp.port $PORT -sudo systemctl start adbd +if [ -f /EON ]; then + stop adbd + start adbd +else + sudo systemctl start adbd +fi IP=$(echo $SSH_CONNECTION | awk '{ print $3}') echo "then, connect on your computer:" diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/vw_mqb_config.py index c55a058159b147..1dd28d371fae64 100755 --- a/selfdrive/debug/vw_mqb_config.py +++ b/selfdrive/debug/vw_mqb_config.py @@ -23,7 +23,7 @@ class ACCESS_TYPE_LEVEL_1(IntEnum): desc_text = "Shows Volkswagen EPS software and coding info, and enables or disables Heading Control Assist " + \ "(Lane Assist). Useful for enabling HCA on cars without factory Lane Assist that want to use " + \ "openpilot integrated at the CAN gateway (J533)." - epilog_text = "This tool is meant to run directly on a vehicle-installed comma three, with the " + \ + epilog_text = "This tool is meant to run directly on a vehicle-installed comma two or comma three, with the " + \ "openpilot/tmux processes stopped. It should also work on a separate PC with a USB-attached comma " + \ "panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must " + \ "turn ignition off and on again for any changes to take effect." diff --git a/selfdrive/hardware/__init__.py b/selfdrive/hardware/__init__.py index 03dfce86d76213..3babf1bb5d3abb 100644 --- a/selfdrive/hardware/__init__.py +++ b/selfdrive/hardware/__init__.py @@ -2,14 +2,18 @@ from typing import cast from selfdrive.hardware.base import HardwareBase +from selfdrive.hardware.eon.hardware import Android from selfdrive.hardware.tici.hardware import Tici from selfdrive.hardware.pc.hardware import Pc +EON = os.path.isfile('/EON') TICI = os.path.isfile('/TICI') -PC = not TICI +PC = not (EON or TICI) -if TICI: +if EON: + HARDWARE = cast(HardwareBase, Android()) +elif TICI: HARDWARE = cast(HardwareBase, Tici()) else: HARDWARE = cast(HardwareBase, Pc()) diff --git a/selfdrive/hardware/base.h b/selfdrive/hardware/base.h index 2826d09700589d..05e55cc0340c66 100644 --- a/selfdrive/hardware/base.h +++ b/selfdrive/hardware/base.h @@ -20,5 +20,6 @@ class HardwareNone { static void set_ssh_enabled(bool enabled) {} static bool PC() { return false; } + static bool EON() { return false; } static bool TICI() { return false; } }; diff --git a/selfdrive/hardware/eon/__init__.py b/selfdrive/hardware/eon/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/hardware/eon/androidd.py b/selfdrive/hardware/eon/androidd.py new file mode 100755 index 00000000000000..3d91468b908505 --- /dev/null +++ b/selfdrive/hardware/eon/androidd.py @@ -0,0 +1,91 @@ +#!/usr/bin/env python3 +import os +import time +import psutil +from typing import Optional + +import cereal.messaging as messaging +from common.realtime import set_core_affinity, set_realtime_priority +from selfdrive.swaglog import cloudlog + + +MAX_MODEM_CRASHES = 3 +MODEM_PATH = "/sys/devices/soc/2080000.qcom,mss/subsys5" +WATCHED_PROCS = ["zygote", "zygote64", "system_server", "/system/bin/servicemanager", "/system/bin/surfaceflinger"] + + +def get_modem_crash_count() -> Optional[int]: + try: + with open(os.path.join(MODEM_PATH, "crash_count")) as f: + return int(f.read()) + except Exception: + cloudlog.exception("Error reading modem crash count") + return None + +def get_modem_state() -> str: + try: + with open(os.path.join(MODEM_PATH, "state")) as f: + return f.read().strip() + except Exception: + cloudlog.exception("Error reading modem state") + return "" + +def main(): + set_core_affinity(1) + set_realtime_priority(1) + + procs = {} + crash_count = 0 + modem_killed = False + modem_state = "ONLINE" + androidLog = messaging.sub_sock('androidLog') + + while True: + # check critical android services + if any(p is None or not p.is_running() for p in procs.values()) or not len(procs): + cur = {p: None for p in WATCHED_PROCS} + for p in psutil.process_iter(attrs=['cmdline']): + cmdline = None if not len(p.info['cmdline']) else p.info['cmdline'][0] + if cmdline in WATCHED_PROCS: + cur[cmdline] = p + + if len(procs): + for p in WATCHED_PROCS: + if cur[p] != procs[p]: + cloudlog.event("android service pid changed", proc=p, cur=cur[p], prev=procs[p], error=True) + procs.update(cur) + + # log caught NetworkPolicy exceptions + msgs = messaging.drain_sock(androidLog) + for m in msgs: + try: + if m.androidLog.tag == "NetworkPolicy" and m.androidLog.message.startswith("problem with advise persist threshold"): + cloudlog.event("network policy exception caught", androidLog=m.androidLog, error=True) + except UnicodeDecodeError: + pass + + if os.path.exists(MODEM_PATH): + # check modem state + state = get_modem_state() + if state != modem_state and not modem_killed: + cloudlog.event("modem state changed", state=state) + modem_state = state + + # check modem crashes + cnt = get_modem_crash_count() + if cnt is not None: + if cnt > crash_count: + cloudlog.event("modem crash", count=cnt) + crash_count = cnt + + # handle excessive modem crashes + if crash_count > MAX_MODEM_CRASHES and not modem_killed: + cloudlog.event("killing modem", error=True) + with open("/sys/kernel/debug/msm_subsys/modem", "w") as f: + f.write("put") + modem_killed = True + + time.sleep(1) + +if __name__ == "__main__": + main() diff --git a/selfdrive/hardware/eon/hardware.h b/selfdrive/hardware/eon/hardware.h new file mode 100644 index 00000000000000..bcd1aaba740302 --- /dev/null +++ b/selfdrive/hardware/eon/hardware.h @@ -0,0 +1,73 @@ +#pragma once + +#include +#include + +#include +#include +#include + +#include "selfdrive/common/util.h" +#include "selfdrive/hardware/base.h" + +class HardwareEon : public HardwareNone { +public: + static constexpr float MAX_VOLUME = 1.0; + static constexpr float MIN_VOLUME = 0.5; + + static bool EON() { return true; } + static std::string get_os_version() { + return "NEOS " + util::read_file("/VERSION"); + }; + + static void reboot() { std::system("reboot"); }; + static void poweroff() { std::system("LD_LIBRARY_PATH= svc power shutdown"); }; + static void set_brightness(int percent) { + std::ofstream brightness_control("/sys/class/leds/lcd-backlight/brightness"); + if (brightness_control.is_open()) { + brightness_control << (int)(percent * (255/100.)) << "\n"; + brightness_control.close(); + } + }; + static void set_display_power(bool on) { + auto dtoken = android::SurfaceComposerClient::getBuiltInDisplay(android::ISurfaceComposer::eDisplayIdMain); + android::SurfaceComposerClient::setDisplayPowerMode(dtoken, on ? HWC_POWER_MODE_NORMAL : HWC_POWER_MODE_OFF); + }; + + static bool get_ssh_enabled() { + return std::system("getprop persist.neos.ssh | grep -qF '1'") == 0; + }; + static void set_ssh_enabled(bool enabled) { + std::string cmd = util::string_format("setprop persist.neos.ssh %d", enabled ? 1 : 0); + std::system(cmd.c_str()); + }; + + // android only + inline static bool launched_activity = false; + static void check_activity() { + int ret = std::system("dumpsys SurfaceFlinger --list | grep -Fq 'com.android.settings'"); + launched_activity = ret == 0; + } + + static void close_activities() { + if(launched_activity) { + std::system("pm disable com.android.settings && pm enable com.android.settings"); + } + } + + static void launch_activity(std::string activity, std::string opts = "") { + if (!launched_activity) { + std::string cmd = "am start -n " + activity + " " + opts + + " --ez extra_prefs_show_button_bar true \ + --es extra_prefs_set_next_text ''"; + std::system(cmd.c_str()); + } + launched_activity = true; + } + static void launch_wifi() { + launch_activity("com.android.settings/.wifi.WifiPickerActivity", "-a android.net.wifi.PICK_WIFI_NETWORK"); + } + static void launch_tethering() { + launch_activity("com.android.settings/.TetherSettings"); + } +}; diff --git a/selfdrive/hardware/eon/hardware.py b/selfdrive/hardware/eon/hardware.py new file mode 100644 index 00000000000000..bd2a01cf1e4aae --- /dev/null +++ b/selfdrive/hardware/eon/hardware.py @@ -0,0 +1,425 @@ +import binascii +import itertools +import os +import re +import serial +import struct +import subprocess +from typing import List, Union + +from cereal import log +from selfdrive.hardware.base import HardwareBase, ThermalConfig + +try: + from common.params import Params +except Exception: + # openpilot is not built yet + Params = None + +NetworkType = log.DeviceState.NetworkType +NetworkStrength = log.DeviceState.NetworkStrength + +MODEM_PATH = "/dev/smd11" + +def service_call(call: List[str]) -> Union[bytes, None]: + try: + ret = subprocess.check_output(["service", "call", *call], encoding='utf8').strip() + if 'Parcel' not in ret: + return None + return parse_service_call_bytes(ret) + except subprocess.CalledProcessError: + return None + + +def parse_service_call_unpack(r, fmt) -> Union[bytes, None]: + try: + return struct.unpack(fmt, r)[0] + except Exception: + return None + + +def parse_service_call_string(r: bytes) -> Union[str, None]: + try: + r = r[8:] # Cut off length field + r_str = r.decode('utf_16_be') + + # All pairs of two characters seem to be swapped. Not sure why + result = "" + for a, b, in itertools.zip_longest(r_str[::2], r_str[1::2], fillvalue='\x00'): + result += b + a + + return result.replace('\x00', '') + except Exception: + return None + + +def parse_service_call_bytes(ret: str) -> Union[bytes, None]: + try: + r = b"" + for hex_part in re.findall(r'[ (]([0-9a-f]{8})', ret): + r += binascii.unhexlify(hex_part) + return r + except Exception: + return None + + +def getprop(key: str) -> Union[str, None]: + try: + return subprocess.check_output(["getprop", key], encoding='utf8').strip() + except subprocess.CalledProcessError: + return None + + +class Android(HardwareBase): + def get_os_version(self): + with open("/VERSION") as f: + return f.read().strip() + + def get_device_type(self): + try: + if int(Params().get("LastPeripheralPandaType")) == log.PandaState.PandaType.uno: + return "two" + except Exception: + pass + return "eon" + + def get_sound_card_online(self): + return (os.path.isfile('/proc/asound/card0/state') and + open('/proc/asound/card0/state').read().strip() == 'ONLINE') + + def get_imei(self, slot): + slot = str(slot) + if slot not in ("0", "1"): + raise ValueError("SIM slot must be 0 or 1") + + return parse_service_call_string(service_call(["iphonesubinfo", "3", "i32", str(slot)])) + + def get_serial(self): + ret = getprop("ro.serialno") + if len(ret) == 0: + ret = "cccccccc" + return ret + + def get_subscriber_info(self): + ret = parse_service_call_string(service_call(["iphonesubinfo", "7"])) + if ret is None or len(ret) < 8: + return "" + return ret + + def reboot(self, reason=None): + # e.g. reason="recovery" to go into recover mode + if reason is None: + reason_args = ["null"] + else: + reason_args = ["s16", reason] + + subprocess.check_output([ + "service", "call", "power", "16", # IPowerManager.reboot + "i32", "0", # no confirmation, + *reason_args, + "i32", "1" # wait + ]) + + def uninstall(self): + with open('/cache/recovery/command', 'w') as f: + f.write('--wipe_data\n') + # IPowerManager.reboot(confirm=false, reason="recovery", wait=true) + self.reboot(reason="recovery") + + def get_sim_info(self): + # Used for athena + # TODO: build using methods from this class + sim_state = getprop("gsm.sim.state").split(",") + network_type = getprop("gsm.network.type").split(',') + mcc_mnc = getprop("gsm.sim.operator.numeric") or None + + sim_id = parse_service_call_string(service_call(['iphonesubinfo', '11'])) + cell_data_state = parse_service_call_unpack(service_call(['phone', '46']), ">q") + cell_data_connected = (cell_data_state == 2) + + return { + 'sim_id': sim_id, + 'mcc_mnc': mcc_mnc, + 'network_type': network_type, + 'sim_state': sim_state, + 'data_connected': cell_data_connected + } + + def get_network_info(self): + msg = log.DeviceState.NetworkInfo.new_message() + msg.state = getprop("gsm.sim.state") or "" + msg.technology = getprop("gsm.network.type") or "" + msg.operator = getprop("gsm.sim.operator.numeric") or "" + + try: + modem = serial.Serial(MODEM_PATH, 115200, timeout=0.1) + modem.write(b"AT$QCRSRP?\r") + msg.extra = modem.read_until(b"OK\r\n").decode('utf-8') + + rsrp = msg.extra.split("$QCRSRP: ")[1].split("\r")[0].split(",") + msg.channel = int(rsrp[1]) + except Exception: + pass + + return msg + + def get_network_type(self): + wifi_check = parse_service_call_string(service_call(["connectivity", "2"])) + if wifi_check is None: + return NetworkType.none + elif 'WIFI' in wifi_check: + return NetworkType.wifi + else: + cell_check = parse_service_call_unpack(service_call(['phone', '59']), ">q") + # from TelephonyManager.java + cell_networks = { + 0: NetworkType.none, + 1: NetworkType.cell2G, + 2: NetworkType.cell2G, + 3: NetworkType.cell3G, + 4: NetworkType.cell2G, + 5: NetworkType.cell3G, + 6: NetworkType.cell3G, + 7: NetworkType.cell3G, + 8: NetworkType.cell3G, + 9: NetworkType.cell3G, + 10: NetworkType.cell3G, + 11: NetworkType.cell2G, + 12: NetworkType.cell3G, + 13: NetworkType.cell4G, + 14: NetworkType.cell4G, + 15: NetworkType.cell3G, + 16: NetworkType.cell2G, + 17: NetworkType.cell3G, + 18: NetworkType.cell4G, + 19: NetworkType.cell4G + } + return cell_networks.get(cell_check, NetworkType.none) + + def get_network_strength(self, network_type): + network_strength = NetworkStrength.unknown + + # from SignalStrength.java + def get_lte_level(rsrp, rssnr): + INT_MAX = 2147483647 + if rsrp == INT_MAX: + lvl_rsrp = NetworkStrength.unknown + elif rsrp >= -95: + lvl_rsrp = NetworkStrength.great + elif rsrp >= -105: + lvl_rsrp = NetworkStrength.good + elif rsrp >= -115: + lvl_rsrp = NetworkStrength.moderate + else: + lvl_rsrp = NetworkStrength.poor + if rssnr == INT_MAX: + lvl_rssnr = NetworkStrength.unknown + elif rssnr >= 45: + lvl_rssnr = NetworkStrength.great + elif rssnr >= 10: + lvl_rssnr = NetworkStrength.good + elif rssnr >= -30: + lvl_rssnr = NetworkStrength.moderate + else: + lvl_rssnr = NetworkStrength.poor + return max(lvl_rsrp, lvl_rssnr) + + def get_tdscdma_level(tdscmadbm): + lvl = NetworkStrength.unknown + if tdscmadbm > -25: + lvl = NetworkStrength.unknown + elif tdscmadbm >= -49: + lvl = NetworkStrength.great + elif tdscmadbm >= -73: + lvl = NetworkStrength.good + elif tdscmadbm >= -97: + lvl = NetworkStrength.moderate + elif tdscmadbm >= -110: + lvl = NetworkStrength.poor + return lvl + + def get_gsm_level(asu): + if asu <= 2 or asu == 99: + lvl = NetworkStrength.unknown + elif asu >= 12: + lvl = NetworkStrength.great + elif asu >= 8: + lvl = NetworkStrength.good + elif asu >= 5: + lvl = NetworkStrength.moderate + else: + lvl = NetworkStrength.poor + return lvl + + def get_evdo_level(evdodbm, evdosnr): + lvl_evdodbm = NetworkStrength.unknown + lvl_evdosnr = NetworkStrength.unknown + if evdodbm >= -65: + lvl_evdodbm = NetworkStrength.great + elif evdodbm >= -75: + lvl_evdodbm = NetworkStrength.good + elif evdodbm >= -90: + lvl_evdodbm = NetworkStrength.moderate + elif evdodbm >= -105: + lvl_evdodbm = NetworkStrength.poor + if evdosnr >= 7: + lvl_evdosnr = NetworkStrength.great + elif evdosnr >= 5: + lvl_evdosnr = NetworkStrength.good + elif evdosnr >= 3: + lvl_evdosnr = NetworkStrength.moderate + elif evdosnr >= 1: + lvl_evdosnr = NetworkStrength.poor + return max(lvl_evdodbm, lvl_evdosnr) + + def get_cdma_level(cdmadbm, cdmaecio): + lvl_cdmadbm = NetworkStrength.unknown + lvl_cdmaecio = NetworkStrength.unknown + if cdmadbm >= -75: + lvl_cdmadbm = NetworkStrength.great + elif cdmadbm >= -85: + lvl_cdmadbm = NetworkStrength.good + elif cdmadbm >= -95: + lvl_cdmadbm = NetworkStrength.moderate + elif cdmadbm >= -100: + lvl_cdmadbm = NetworkStrength.poor + if cdmaecio >= -90: + lvl_cdmaecio = NetworkStrength.great + elif cdmaecio >= -110: + lvl_cdmaecio = NetworkStrength.good + elif cdmaecio >= -130: + lvl_cdmaecio = NetworkStrength.moderate + elif cdmaecio >= -150: + lvl_cdmaecio = NetworkStrength.poor + return max(lvl_cdmadbm, lvl_cdmaecio) + + if network_type == NetworkType.none: + return network_strength + if network_type == NetworkType.wifi: + out = subprocess.check_output('dumpsys connectivity', shell=True).decode('utf-8') + network_strength = NetworkStrength.unknown + for line in out.split('\n'): + signal_str = "SignalStrength: " + if signal_str in line: + lvl_idx_start = line.find(signal_str) + len(signal_str) + lvl_idx_end = line.find(']', lvl_idx_start) + lvl = int(line[lvl_idx_start : lvl_idx_end]) + if lvl >= -50: + network_strength = NetworkStrength.great + elif lvl >= -60: + network_strength = NetworkStrength.good + elif lvl >= -70: + network_strength = NetworkStrength.moderate + else: + network_strength = NetworkStrength.poor + return network_strength + else: + # check cell strength + out = subprocess.check_output('dumpsys telephony.registry', shell=True).decode('utf-8') + for line in out.split('\n'): + if "mSignalStrength" in line: + arr = line.split(' ') + ns = 0 + if ("gsm" in arr[14]): + rsrp = int(arr[9]) + rssnr = int(arr[11]) + ns = get_lte_level(rsrp, rssnr) + if ns == NetworkStrength.unknown: + tdscmadbm = int(arr[13]) + ns = get_tdscdma_level(tdscmadbm) + if ns == NetworkStrength.unknown: + asu = int(arr[1]) + ns = get_gsm_level(asu) + else: + cdmadbm = int(arr[3]) + cdmaecio = int(arr[4]) + evdodbm = int(arr[5]) + evdosnr = int(arr[7]) + lvl_cdma = get_cdma_level(cdmadbm, cdmaecio) + lvl_edmo = get_evdo_level(evdodbm, evdosnr) + if lvl_edmo == NetworkStrength.unknown: + ns = lvl_cdma + elif lvl_cdma == NetworkStrength.unknown: + ns = lvl_edmo + else: + ns = min(lvl_cdma, lvl_edmo) + network_strength = max(network_strength, ns) + + return network_strength + + def get_battery_capacity(self): + return self.read_param_file("/sys/class/power_supply/battery/capacity", int, 100) + + def get_battery_status(self): + # This does not correspond with actual charging or not. + # If a USB cable is plugged in, it responds with 'Charging', even when charging is disabled + return self.read_param_file("/sys/class/power_supply/battery/status", lambda x: x.strip(), '') + + def get_battery_current(self): + return self.read_param_file("/sys/class/power_supply/battery/current_now", int) + + def get_battery_voltage(self): + return self.read_param_file("/sys/class/power_supply/battery/voltage_now", int) + + def get_battery_charging(self): + # This does correspond with actually charging + return self.read_param_file("/sys/class/power_supply/battery/charge_type", lambda x: x.strip() != "N/A", True) + + def set_battery_charging(self, on): + with open('/sys/class/power_supply/battery/charging_enabled', 'w') as f: + f.write(f"{1 if on else 0}\n") + + def get_usb_present(self): + return self.read_param_file("/sys/class/power_supply/usb/present", lambda x: bool(int(x)), False) + + def get_current_power_draw(self): + if self.get_battery_status() == 'Discharging': + # If the battery is discharging, we can use this measurement + # On C2: this is low by about 10-15%, probably mostly due to UNO draw not being factored in + return ((self.get_battery_voltage() / 1000000) * (self.get_battery_current() / 1000000)) + else: + # We don't have a good direct way to measure this if it's not "discharging" + return None + + def shutdown(self): + os.system('LD_LIBRARY_PATH="" svc power shutdown') + + def get_thermal_config(self): + # the thermal sensors on the 820 don't have meaningful names + return ThermalConfig(cpu=((5, 7, 10, 12), 10), gpu=((16,), 10), mem=(2, 10), + bat=("battery", 1000), ambient=("pa_therm0", 1), pmic=(("pm8994_tz",), 1000)) + + def set_screen_brightness(self, percentage): + with open("/sys/class/leds/lcd-backlight/brightness", "w") as f: + f.write(str(int(percentage * 2.55))) + + def get_screen_brightness(self): + try: + with open("/sys/class/leds/lcd-backlight/brightness") as f: + return int(float(f.read()) / 2.55) + except Exception: + return 0 + + def set_power_save(self, powersave_enabled): + pass + + def get_gpu_usage_percent(self): + try: + used, total = open('/sys/devices/soc/b00000.qcom,kgsl-3d0/kgsl/kgsl-3d0/gpubusy').read().strip().split() + perc = 100.0 * int(used) / int(total) + return min(max(perc, 0), 100) + except Exception: + return 0 + + def get_modem_temperatures(self): + # Not sure if we can get this on the LeEco + return [] + + def get_nvme_temperatures(self): + return [] + + def initialize_hardware(self): + pass + + def get_networks(self): + return None diff --git a/selfdrive/hardware/eon/neos.json b/selfdrive/hardware/eon/neos.json new file mode 100644 index 00000000000000..4010f7126a0892 --- /dev/null +++ b/selfdrive/hardware/eon/neos.json @@ -0,0 +1,7 @@ +{ + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7.zip", + "ota_hash": "50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7", + "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f.img", + "recovery_len": 15222060, + "recovery_hash": "fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f" +} diff --git a/selfdrive/hardware/eon/neos.py b/selfdrive/hardware/eon/neos.py new file mode 100755 index 00000000000000..6f290fbcd19e5d --- /dev/null +++ b/selfdrive/hardware/eon/neos.py @@ -0,0 +1,130 @@ +#!/usr/bin/env python3 +import argparse +import hashlib +import json +import logging +import os +import requests + +NEOSUPDATE_DIR = "/data/neoupdate" + +RECOVERY_DEV = "/dev/block/bootdevice/by-name/recovery" +RECOVERY_COMMAND = "/cache/recovery/command" + + +def get_fn(url: str): + return os.path.join(NEOSUPDATE_DIR, os.path.basename(url)) + + +def download_file(url: str, fn: str, sha256: str, display_name: str, cloudlog=logging) -> None: + # check if already downloaded + if check_hash(fn, sha256): + cloudlog.info(f"{display_name} already cached") + return + + try: + with open(fn, "ab+") as f: + headers = {"Range": f"bytes={f.tell()}-"} + r = requests.get(url, stream=True, allow_redirects=True, headers=headers) + r.raise_for_status() + + total = int(r.headers['Content-Length']) + if 'Content-Range' in r.headers: + total = int(r.headers['Content-Range'].split('/')[-1]) + + for chunk in r.iter_content(chunk_size=1024 * 1024): + f.write(chunk) + print(f"Downloading {display_name}: {f.tell() / total * 100}", flush=True) + except Exception: + cloudlog.error("download error") + if os.path.isfile(fn): + os.unlink(fn) + raise + + if not check_hash(fn, sha256): + if os.path.isfile(fn): + os.unlink(fn) + raise Exception("downloaded update failed hash check") + + +def check_hash(fn: str, sha256: str, length: int = -1) -> bool: + if not os.path.exists(fn): + return False + + h = hashlib.sha256() + with open(fn, "rb") as f: + while f.tell() != length: + r = min(max(0, length - f.tell()), 1024 * 1024) if length > 0 else 1024 * 1024 + dat = f.read(r) + if not dat: + break + h.update(dat) + return h.hexdigest().lower() == sha256.lower() + + +def flash_update(update_fn: str, out_path: str) -> None: + with open(update_fn, "rb") as update, open(out_path, "w+b") as out: + while True: + dat = update.read(8192) + if len(dat) == 0: + break + out.write(dat) + + +def download_neos_update(manifest_path: str, cloudlog=logging) -> None: + with open(manifest_path) as f: + m = json.load(f) + + os.makedirs(NEOSUPDATE_DIR, exist_ok=True) + + # handle recovery updates + if not check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len']): + cloudlog.info("recovery needs update") + recovery_fn = os.path.join(NEOSUPDATE_DIR, os.path.basename(m['recovery_url'])) + download_file(m['recovery_url'], recovery_fn, m['recovery_hash'], "recovery", cloudlog) + + flash_update(recovery_fn, RECOVERY_DEV) + assert check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len']), "recovery flash corrupted" + cloudlog.info("recovery successfully flashed") + + # download OTA update + download_file(m['ota_url'], get_fn(m['ota_url']), m['ota_hash'], "system", cloudlog) + + +def verify_update_ready(manifest_path: str) -> bool: + with open(manifest_path) as f: + m = json.load(f) + + ota_downloaded = check_hash(get_fn(m['ota_url']), m['ota_hash']) + recovery_flashed = check_hash(RECOVERY_DEV, m['recovery_hash'], m['recovery_len']) + return ota_downloaded and recovery_flashed + + +def perform_ota_update(manifest_path: str) -> None: + with open(manifest_path) as f: + m = json.load(f) + + # reboot into recovery + ota_fn = get_fn(m['ota_url']) + with open(RECOVERY_COMMAND, "w") as rf: + rf.write(f"--update_package={ota_fn}\n") + os.system("service call power 16 i32 0 s16 recovery i32 1") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="NEOS update utility", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument("--swap", action="store_true", help="Peform update after downloading") + parser.add_argument("--swap-if-ready", action="store_true", help="Perform update if already downloaded") + parser.add_argument("manifest", help="Manifest json") + args = parser.parse_args() + + logging.basicConfig(level=logging.INFO) + + if args.swap_if_ready: + if verify_update_ready(args.manifest): + perform_ota_update(args.manifest) + else: + download_neos_update(args.manifest, logging) + if args.swap: + perform_ota_update(args.manifest) diff --git a/selfdrive/hardware/eon/shutdownd.py b/selfdrive/hardware/eon/shutdownd.py new file mode 100755 index 00000000000000..15112e7d5ee300 --- /dev/null +++ b/selfdrive/hardware/eon/shutdownd.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python3 +import os +import time +import datetime + +from common.params import Params +from selfdrive.hardware.eon.hardware import getprop +from selfdrive.swaglog import cloudlog + +def main(): + prev = b"" + params = Params() + while True: + with open("/dev/__properties__", 'rb') as f: + cur = f.read() + + if cur != prev: + prev = cur + + # 0 for shutdown, 1 for reboot + prop = getprop("sys.shutdown.requested") + if prop is not None and len(prop) > 0: + os.system("pkill -9 loggerd") + params.put("LastSystemShutdown", f"'{prop}' {datetime.datetime.now()}") + os.sync() + + time.sleep(120) + cloudlog.error('shutdown false positive') + break + + time.sleep(0.1) + +if __name__ == "__main__": + main() diff --git a/selfdrive/hardware/eon/test_neos_updater.py b/selfdrive/hardware/eon/test_neos_updater.py new file mode 100755 index 00000000000000..e258f943d20432 --- /dev/null +++ b/selfdrive/hardware/eon/test_neos_updater.py @@ -0,0 +1,145 @@ +#!/usr/bin/env python3 +import hashlib +import http.server +import json +import os +import unittest +import random +import requests +import shutil +import socketserver +import tempfile +import multiprocessing +from pathlib import Path + +from selfdrive.hardware.eon.neos import RECOVERY_DEV, NEOSUPDATE_DIR, get_fn, download_file, \ + verify_update_ready, download_neos_update + +EON_DIR = os.path.join(os.path.dirname(os.path.abspath(__file__))) +MANIFEST = os.path.join(EON_DIR, "neos.json") + +PORT = 8000 + +def server_thread(port): + socketserver.TCPServer.allow_reuse_address = True + httpd = socketserver.TCPServer(("", port), http.server.SimpleHTTPRequestHandler) + httpd.serve_forever() + + +class TestNeosUpdater(unittest.TestCase): + + @classmethod + def setUpClass(cls): + # generate a fake manifest + cls.manifest = {} + for i in ('ota', 'recovery'): + with tempfile.NamedTemporaryFile(delete=False, dir=os.getcwd()) as f: + dat = os.urandom(random.randint(1000, 100000)) + f.write(dat) + cls.manifest[f"{i}_url"] = f"http://localhost:{PORT}/" + os.path.relpath(f.name) + cls.manifest[F"{i}_hash"] = hashlib.sha256(dat).hexdigest() + if i == "recovery": + cls.manifest["recovery_len"] = len(dat) + + with tempfile.NamedTemporaryFile(delete=False, mode='w') as f: + f.write(json.dumps(cls.manifest)) + cls.fake_manifest = f.name + + @classmethod + def tearDownClass(cls): + os.unlink(cls.fake_manifest) + os.unlink(os.path.basename(cls.manifest['ota_url'])) + os.unlink(os.path.basename(cls.manifest['recovery_url'])) + + def setUp(self): + # server for update files + self.server = multiprocessing.Process(target=server_thread, args=(PORT, )) + self.server.start() + + # clean up + if os.path.exists(NEOSUPDATE_DIR): + shutil.rmtree(NEOSUPDATE_DIR) + + def tearDown(self): + self.server.kill() + self.server.join(1) + + def _corrupt_recovery(self): + with open(RECOVERY_DEV, "wb") as f: + f.write(b'\x00'*100) + + def test_manifest(self): + with open(MANIFEST) as f: + m = json.load(f) + + assert m['ota_hash'] in m['ota_url'] + assert m['recovery_hash'] in m['recovery_url'] + assert m['recovery_len'] > 0 + + for url in (m['ota_url'], m['recovery_url']): + r = requests.head(m['recovery_url']) + r.raise_for_status() + self.assertEqual(r.headers['Content-Type'], "application/octet-stream") + if url == m['recovery_url']: + self.assertEqual(int(r.headers['Content-Length']), m['recovery_len']) + + def test_download_hash_check(self): + os.makedirs(NEOSUPDATE_DIR, exist_ok=True) + Path(get_fn(self.manifest['ota_url'])).touch() + with self.assertRaisesRegex(Exception, "failed hash check"): + download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']), + self.manifest['ota_hash']+'a', "system") + + # should've unlinked after the failed hash check, should succeed now + download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']), + self.manifest['ota_hash'], "system") + + # TODO: needs an http server that supports Content-Range + #def test_download_resume(self): + # os.makedirs(NEOSUPDATE_DIR, exist_ok=True) + # with open(os.path.basename(self.manifest['ota_url']), "rb") as src, \ + # open(get_fn(self.manifest['ota_url']), "wb") as dest: + # l = dest.write(src.read(8192)) + # assert l == 8192 + # download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']), + # self.manifest['ota_hash'], "system") + + def test_download_no_internet(self): + self.server.kill() + os.makedirs(NEOSUPDATE_DIR, exist_ok=True) + # fail, no internet + with self.assertRaises(requests.exceptions.ConnectionError): + download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']), + self.manifest['ota_hash'], "system") + + # already cached, ensure we don't hit the server + shutil.copyfile(os.path.basename(self.manifest['ota_url']), get_fn(self.manifest['ota_url'])) + download_file(self.manifest['ota_url'], get_fn(self.manifest['ota_url']), + self.manifest['ota_hash'], "system") + + + def test_download_update(self): + download_neos_update(self.fake_manifest) + self.assertTrue(verify_update_ready(self.fake_manifest)) + + def test_verify_update(self): + # good state + download_neos_update(self.fake_manifest) + self.assertTrue(verify_update_ready(self.fake_manifest)) + + # corrupt recovery + self._corrupt_recovery() + self.assertFalse(verify_update_ready(self.fake_manifest)) + + # back to good state + download_neos_update(self.fake_manifest) + self.assertTrue(verify_update_ready(self.fake_manifest)) + + # corrupt ota + self._corrupt_recovery() + with open(os.path.join(NEOSUPDATE_DIR, os.path.basename(self.manifest['ota_url'])), "ab") as f: + f.write(b'\x00') + self.assertFalse(verify_update_ready(self.fake_manifest)) + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/hardware/eon/update_neos.sh b/selfdrive/hardware/eon/update_neos.sh new file mode 100755 index 00000000000000..ccc6ecce4496e7 --- /dev/null +++ b/selfdrive/hardware/eon/update_neos.sh @@ -0,0 +1,4 @@ +#!/usr/bin/bash + +ROOT=$PWD/../../.. +$ROOT/installer/updater/updater "file://$ROOT/installer/updater/update.json" diff --git a/selfdrive/hardware/eon/updater b/selfdrive/hardware/eon/updater new file mode 100755 index 00000000000000..eaf34e957ceb32 Binary files /dev/null and b/selfdrive/hardware/eon/updater differ diff --git a/selfdrive/hardware/hw.h b/selfdrive/hardware/hw.h index b221b63db25756..f18ede01ec25cc 100644 --- a/selfdrive/hardware/hw.h +++ b/selfdrive/hardware/hw.h @@ -3,7 +3,10 @@ #include "selfdrive/hardware/base.h" #include "selfdrive/common/util.h" -#if QCOM2 +#ifdef QCOM +#include "selfdrive/hardware/eon/hardware.h" +#define Hardware HardwareEon +#elif QCOM2 #include "selfdrive/hardware/tici/hardware.h" #define Hardware HardwareTici #else diff --git a/selfdrive/logcatd/SConscript b/selfdrive/logcatd/SConscript index 6bd7c6ff3e8561..8811f32fe65118 100644 --- a/selfdrive/logcatd/SConscript +++ b/selfdrive/logcatd/SConscript @@ -1,3 +1,6 @@ -Import('env', 'cereal', 'messaging', 'common') +Import('env', 'cereal', 'messaging', 'common', 'arch') -env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, common, 'zmq', 'capnp', 'kj', 'systemd', 'json11']) +if arch == "aarch64": + env.Program('logcatd', 'logcatd_android.cc', LIBS=[cereal, messaging, common, 'cutils', 'zmq', 'capnp', 'kj']) +else: + env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, common, 'zmq', 'capnp', 'kj', 'systemd', 'json11']) diff --git a/selfdrive/logcatd/logcatd_android.cc b/selfdrive/logcatd/logcatd_android.cc new file mode 100644 index 00000000000000..8c2524d94a0949 --- /dev/null +++ b/selfdrive/logcatd/logcatd_android.cc @@ -0,0 +1,51 @@ +#include +#include +#include +#include + +#include + +#include "cereal/messaging/messaging.h" + +#undef LOG_ID_KERNEL +#define LOG_ID_KERNEL 5 + +int main() { + std::signal(SIGINT, exit); + std::signal(SIGTERM, exit); + setpriority(PRIO_PROCESS, 0, -15); + + // setup android logging + logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0); + assert(logger_list); + for (auto log_id : {LOG_ID_MAIN, LOG_ID_RADIO, LOG_ID_SYSTEM, LOG_ID_CRASH, (log_id_t)LOG_ID_KERNEL}) { + logger *logger = android_logger_open(logger_list, log_id); + assert(logger); + } + + PubMaster pm({"androidLog"}); + + while (true) { + log_msg log_msg; + int err = android_logger_list_read(logger_list, &log_msg); + if (err <= 0) break; + + AndroidLogEntry entry; + err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); + if (err < 0) continue; + + MessageBuilder msg; + auto androidEntry = msg.initEvent().initAndroidLog(); + androidEntry.setId(log_msg.id()); + androidEntry.setTs(entry.tv_sec * NS_PER_SEC + entry.tv_nsec); + androidEntry.setPriority(entry.priority); + androidEntry.setPid(entry.pid); + androidEntry.setTid(entry.tid); + androidEntry.setTag(entry.tag); + androidEntry.setMessage(entry.message); + pm.send("androidLog", msg); + } + + android_logger_list_free(logger_list); + return 0; +} diff --git a/selfdrive/logcatd/tests/test_logcatd_android.py b/selfdrive/logcatd/tests/test_logcatd_android.py new file mode 100755 index 00000000000000..4e0c903dfa9959 --- /dev/null +++ b/selfdrive/logcatd/tests/test_logcatd_android.py @@ -0,0 +1,45 @@ +#!/usr/bin/env python3 +import os +import random +import string +import time +import unittest +import uuid + +import cereal.messaging as messaging +from selfdrive.test.helpers import with_processes + +class TestLogcatdAndroid(unittest.TestCase): + + @with_processes(['logcatd']) + def test_log(self): + sock = messaging.sub_sock("androidLog", conflate=False) + + # make sure sockets are ready + time.sleep(1) + messaging.drain_sock(sock) + + sent_msgs = {} + for _ in range(random.randint(2, 10)): + # write some log messages + for __ in range(random.randint(5, 50)): + tag = uuid.uuid4().hex + msg = ''.join(random.choice(string.ascii_letters) for _ in range(random.randrange(2, 50))) + sent_msgs[tag] = {'recv_cnt': 0, 'msg': msg} + os.system(f"log -t '{tag}' '{msg}'") + + time.sleep(1) + msgs = messaging.drain_sock(sock) + for m in msgs: + self.assertTrue(m.valid) + self.assertLess(time.monotonic() - (m.logMonoTime / 1e9), 30) + tag = m.androidLog.tag + if tag in sent_msgs: + sent_msgs[tag]['recv_cnt'] += 1 + self.assertEqual(m.androidLog.message.strip(), sent_msgs[tag]['msg']) + + for v in sent_msgs.values(): + self.assertEqual(v['recv_cnt'], 1) + +if __name__ == "__main__": + unittest.main() diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 92cc37a5fbe058..8a428b7602dccf 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -4,14 +4,19 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon') libs = [common, cereal, messaging, visionipc, 'zmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', - 'yuv', 'bz2', 'OpenCL', 'pthread'] + 'yuv', 'bz2', 'OpenCL'] src = ['logger.cc', 'loggerd.cc', 'video_writer.cc'] -if arch == "larch64": +if arch in ["aarch64", "larch64"]: src += ['omx_encoder.cc'] libs += ['OmxCore', 'gsl', 'CB'] + gpucommon + if arch == "aarch64": + libs += ['OmxVenc', 'cutils'] + else: + libs += ['pthread'] else: src += ['raw_logger.cc'] + libs += ['pthread'] if arch == "Darwin": # fix OpenCL diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index e7ce308cec6f49..a72312484748e1 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -11,6 +11,8 @@ static kj::Array build_boot_log() { if (Hardware::TICI()) { bootlog_commands.push_back("journalctl"); bootlog_commands.push_back("sudo nvme smart-log --output-format=json /dev/nvme0"); + } else if (Hardware::EON()) { + bootlog_commands.push_back("logcat -d"); } MessageBuilder msg; diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index f2c34554e329b2..6ba520d162670a 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -14,6 +14,9 @@ #include #include #include +#ifdef QCOM +#include +#endif #include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" @@ -33,7 +36,9 @@ kj::Array logger_build_init_data() { MessageBuilder msg; auto init = msg.initEvent().initInitData(); - if (Hardware::TICI()) { + if (Hardware::EON()) { + init.setDeviceType(cereal::InitData::DeviceType::NEO); + } else if (Hardware::TICI()) { init.setDeviceType(cereal::InitData::DeviceType::TICI); } else { init.setDeviceType(cereal::InitData::DeviceType::PC); @@ -56,6 +61,20 @@ kj::Array logger_build_init_data() { init.setKernelVersion(util::read_file("/proc/version")); init.setOsVersion(util::read_file("/VERSION")); +#ifdef QCOM + { + std::vector > properties; + property_list(append_property, (void*)&properties); + + auto lentries = init.initAndroidProperties().initEntries(properties.size()); + for (int i=0; i int main(int argc, char** argv) { - if (Hardware::TICI()) { + if (Hardware::EON()) { + setpriority(PRIO_PROCESS, 0, -20); + } else if (Hardware::TICI()) { int ret; ret = util::set_core_affinity({0, 1, 2, 3}); assert(ret == 0); diff --git a/selfdrive/loggerd/tests/test_encoder.py b/selfdrive/loggerd/tests/test_encoder.py index 9479b6256a064a..97c142652f3cab 100755 --- a/selfdrive/loggerd/tests/test_encoder.py +++ b/selfdrive/loggerd/tests/test_encoder.py @@ -13,19 +13,27 @@ from common.params import Params from common.timeout import Timeout -from selfdrive.hardware import TICI +from selfdrive.hardware import EON, TICI from selfdrive.loggerd.config import ROOT from selfdrive.manager.process_config import managed_processes from tools.lib.logreader import LogReader SEGMENT_LENGTH = 2 -FULL_SIZE = 2507572 -CAMERAS = [ - ("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"), - ("dcamera.hevc", 20, FULL_SIZE, "driverEncodeIdx"), - ("ecamera.hevc", 20, FULL_SIZE, "wideRoadEncodeIdx"), - ("qcamera.ts", 20, 77066, None), -] +if EON: + FULL_SIZE = 1253786 # file size for a 2s segment in bytes + CAMERAS = [ + ("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"), + ("dcamera.hevc", 10, 770920, "driverEncodeIdx"), + ("qcamera.ts", 20, 77066, None), + ] +else: + FULL_SIZE = 2507572 + CAMERAS = [ + ("fcamera.hevc", 20, FULL_SIZE, "roadEncodeIdx"), + ("dcamera.hevc", 20, FULL_SIZE, "driverEncodeIdx"), + ("ecamera.hevc", 20, FULL_SIZE, "wideRoadEncodeIdx"), + ("qcamera.ts", 20, 77066, None), + ] # we check frame count, so we don't have to be too strict on size FILE_SIZE_TOLERANCE = 0.5 @@ -36,7 +44,7 @@ class TestEncoder(unittest.TestCase): # TODO: all of loggerd should work on PC @classmethod def setUpClass(cls): - if not TICI: + if not (EON or TICI): raise unittest.SkipTest def setUp(self): @@ -85,6 +93,8 @@ def check_seg(i): if not record_front and "dcamera" in camera: continue + eon_dcam = EON and (camera == 'dcamera.hevc') + file_path = f"{route_prefix_path}--{i}/{camera}" # check file exists @@ -97,7 +107,7 @@ def check_seg(i): cmd = "LD_LIBRARY_PATH=/usr/local/lib " + cmd expected_frames = fps * SEGMENT_LENGTH - frame_tolerance = 0 + frame_tolerance = 1 if eon_dcam else 0 probe = subprocess.check_output(cmd, shell=True, encoding='utf8') frame_count = int(probe.split('\n')[0].strip()) counts.append(frame_count) @@ -130,8 +140,9 @@ def check_seg(i): self.assertTrue(all(valid)) - self.assertEqual(expected_frames * i, encode_idxs[0]) - first_frames.append(frame_idxs[0]) + if not eon_dcam: + self.assertEqual(expected_frames * i, encode_idxs[0]) + first_frames.append(frame_idxs[0]) self.assertEqual(len(set(encode_idxs)), len(encode_idxs)) self.assertEqual(1, len(set(first_frames))) diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 2e2747fecc7651..e3165349815da0 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -1,6 +1,6 @@ import os -from selfdrive.hardware import TICI, PC +from selfdrive.hardware import EON, TICI, PC from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess WEBCAM = os.getenv("USE_WEBCAM") is not None @@ -16,7 +16,7 @@ NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), NativeProcess("navd", "selfdrive/ui/navd", ["./navd"], offroad=True), NativeProcess("proclogd", "selfdrive/proclogd", ["./proclogd"]), - NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC), + NativeProcess("sensord", "selfdrive/sensord", ["./sensord"], enabled=not PC, persistent=EON, sigkill=EON), NativeProcess("ubloxd", "selfdrive/locationd", ["./ubloxd"], enabled=(not PC or WEBCAM)), NativeProcess("ui", "selfdrive/ui", ["./ui"], offroad=True, watchdog_max_dt=(5 if TICI else None)), NativeProcess("soundd", "selfdrive/ui/soundd", ["./soundd"], offroad=True), @@ -41,6 +41,11 @@ NativeProcess("bridge", "cereal/messaging", ["./bridge"], onroad=False, notcar=True), PythonProcess("webjoystick", "tools.joystick.web", onroad=False, notcar=True), + # EON only + PythonProcess("rtshield", "selfdrive.rtshield", enabled=EON), + PythonProcess("shutdownd", "selfdrive.hardware.eon.shutdownd", enabled=EON), + PythonProcess("androidd", "selfdrive.hardware.eon.androidd", enabled=EON, persistent=True), + # Experimental PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")), ] diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py index 1750c81b2e1b25..d16a145031df08 100755 --- a/selfdrive/manager/test/test_manager.py +++ b/selfdrive/manager/test/test_manager.py @@ -5,14 +5,14 @@ import unittest import selfdrive.manager.manager as manager -from selfdrive.hardware import TICI, HARDWARE +from selfdrive.hardware import EON, TICI, HARDWARE from selfdrive.manager.process import DaemonProcess from selfdrive.manager.process_config import managed_processes os.environ['FAKEUPLOAD'] = "1" # TODO: make eon fast -MAX_STARTUP_TIME = 15 +MAX_STARTUP_TIME = 30 if EON else 15 ALL_PROCESSES = [p.name for p in managed_processes.values() if (type(p) is not DaemonProcess) and p.enabled and (p.name not in ['updated', 'pandad'])] @@ -50,7 +50,7 @@ def test_clean_exit(self): self.assertTrue(state.running, f"{p} not running") exit_code = managed_processes[p].stop(retry=False) - if (TICI and p in ['ui', 'navd']): + if (TICI and p in ['ui', 'navd']) or (EON and p == 'logcatd'): # TODO: make Qt UI exit gracefully continue diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index 77d578736764dc..20d3fb8acc6c8f 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -31,8 +31,9 @@ thneed_src = [ use_thneed = not GetOption('no_thneed') -if arch == "larch64": - libs += ['gsl', 'CB', 'pthread', 'dl'] +if arch == "aarch64" or arch == "larch64": + libs += ['gsl', 'CB'] + libs += ['gnustl_shared'] if arch == "aarch64" else ['pthread', 'dl'] if use_thneed: common_src += thneed_src @@ -63,7 +64,7 @@ else: common_model = lenv.Object(common_src) # build thneed model -if use_thneed and arch == "larch64": +if use_thneed and arch in ("aarch64", "larch64"): fn = File("#models/supercombo").abspath compiler = lenv.Program('thneed/compile', ["thneed/compile.cc"]+common_model, LIBS=libs) cmd = f"cd {Dir('.').abspath} && {compiler[0].abspath} {fn}.dlc {fn}_badweights.thneed --binary" diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld index f292fe4c0bd2a4..9acd7bcc33cf40 100755 --- a/selfdrive/modeld/dmonitoringmodeld +++ b/selfdrive/modeld/dmonitoringmodeld @@ -3,10 +3,15 @@ DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" cd $DIR -if [ -f /TICI ]; then - export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH" +if [ -d /system ]; then + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/third_party/snpe/aarch64/:$LD_LIBRARY_PATH" + fi export ADSP_LIBRARY_PATH="/data/pythonpath/third_party/snpe/dsp/" else + # PC export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH" fi exec ./_dmonitoringmodeld diff --git a/selfdrive/modeld/modeld b/selfdrive/modeld/modeld index c067cf3d622489..fcf2812cb7305a 100755 --- a/selfdrive/modeld/modeld +++ b/selfdrive/modeld/modeld @@ -3,9 +3,14 @@ DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" cd $DIR -if [ -f /TICI ]; then - export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH" +if [ -d /system ]; then + if [ -f /TICI ]; then # QCOM2 + export LD_LIBRARY_PATH="/usr/lib/aarch64-linux-gnu:/data/pythonpath/third_party/snpe/larch64:$LD_LIBRARY_PATH" + else # QCOM + export LD_LIBRARY_PATH="/data/pythonpath/third_party/snpe/aarch64/:$LD_LIBRARY_PATH" + fi else + # PC export LD_LIBRARY_PATH="$DIR/../../third_party/snpe/x86_64-linux-clang:$DIR/../../openpilot/third_party/snpe/x86_64:$LD_LIBRARY_PATH" fi exec ./_modeld diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 6ee07b3d021dd4..5da401e92d3446 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -163,11 +163,11 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client_main, VisionIpcCl } int main(int argc, char **argv) { - if (Hardware::TICI()) { + if (!Hardware::PC()) { int ret; ret = util::set_realtime_priority(54); assert(ret == 0); - util::set_core_affinity({7}); + util::set_core_affinity({Hardware::EON() ? 2 : 7}); assert(ret == 0); } diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc index 44fa6ce298c389..0d394ca511e4b1 100644 --- a/selfdrive/modeld/runners/snpemodel.cc +++ b/selfdrive/modeld/runners/snpemodel.cc @@ -18,7 +18,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int output = loutput; output_size = loutput_size; use_extra = luse_extra; -#ifdef QCOM2 +#if defined(QCOM) || defined(QCOM2) if (runtime==USE_GPU_RUNTIME) { Runtime = zdl::DlSystem::Runtime_t::GPU; } else if (runtime==USE_DSP_RUNTIME) { @@ -39,7 +39,7 @@ SNPEModel::SNPEModel(const char *path, float *loutput, size_t loutput_size, int // create model runner zdl::SNPE::SNPEBuilder snpeBuilder(container.get()); while (!snpe) { -#ifdef QCOM2 +#if defined(QCOM) || defined(QCOM2) snpe = snpeBuilder.setOutputLayers({}) .setRuntimeProcessor(Runtime) .setUseUserSuppliedBuffers(true) diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h index 6e9c33f89c8f6d..584c6368026e81 100644 --- a/selfdrive/modeld/runners/snpemodel.h +++ b/selfdrive/modeld/runners/snpemodel.h @@ -38,7 +38,7 @@ class SNPEModel : public RunModel { private: std::string model_data; -#ifdef QCOM2 +#if defined(QCOM) || defined(QCOM2) zdl::DlSystem::Runtime_t Runtime; #endif diff --git a/selfdrive/modeld/thneed/thneed.cc b/selfdrive/modeld/thneed/thneed.cc index 470ff219b0e431..e2dc9b72f22d0a 100644 --- a/selfdrive/modeld/thneed/thneed.cc +++ b/selfdrive/modeld/thneed/thneed.cc @@ -433,7 +433,7 @@ cl_program thneed_clCreateProgramWithSource(cl_context context, cl_uint count, c } void *dlsym(void *handle, const char *symbol) { -#ifdef QCOM2 +#if defined(QCOM) || defined(QCOM2) void *(*my_dlsym)(void *handle, const char *symbol) = (void *(*)(void *handle, const char *symbol))((uintptr_t)dlopen + DLSYM_OFFSET); #else #error "Unsupported platform for thneed" diff --git a/selfdrive/sensord/SConscript b/selfdrive/sensord/SConscript index db32887e7f4073..186e302bc3d4ea 100644 --- a/selfdrive/sensord/SConscript +++ b/selfdrive/sensord/SConscript @@ -1,19 +1,22 @@ Import('env', 'arch', 'common', 'cereal', 'messaging') -sensors = [ - 'sensors/file_sensor.cc', - 'sensors/i2c_sensor.cc', - 'sensors/light_sensor.cc', - 'sensors/bmx055_accel.cc', - 'sensors/bmx055_gyro.cc', - 'sensors/bmx055_magn.cc', - 'sensors/bmx055_temp.cc', - 'sensors/lsm6ds3_accel.cc', - 'sensors/lsm6ds3_gyro.cc', - 'sensors/lsm6ds3_temp.cc', - 'sensors/mmc5603nj_magn.cc', -] -libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj'] -if arch == "larch64": - libs.append('i2c') -env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs) +if arch == "aarch64": + env.Program('_sensord', 'sensors_qcom.cc', LIBS=['hardware', common, cereal, messaging, 'capnp', 'zmq', 'kj']) +else: + sensors = [ + 'sensors/file_sensor.cc', + 'sensors/i2c_sensor.cc', + 'sensors/light_sensor.cc', + 'sensors/bmx055_accel.cc', + 'sensors/bmx055_gyro.cc', + 'sensors/bmx055_magn.cc', + 'sensors/bmx055_temp.cc', + 'sensors/lsm6ds3_accel.cc', + 'sensors/lsm6ds3_gyro.cc', + 'sensors/lsm6ds3_temp.cc', + 'sensors/mmc5603nj_magn.cc', + ] + libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj'] + if arch == "larch64": + libs.append('i2c') + env.Program('_sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs) diff --git a/selfdrive/sensord/sensors_qcom.cc b/selfdrive/sensord/sensors_qcom.cc new file mode 100644 index 00000000000000..fcdb9a72d78fee --- /dev/null +++ b/selfdrive/sensord/sensors_qcom.cc @@ -0,0 +1,228 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/timing.h" +#include "selfdrive/common/util.h" + +// ACCELEROMETER_UNCALIBRATED is only in Android O +// https://developer.android.com/reference/android/hardware/Sensor.html#STRING_TYPE_ACCELEROMETER_UNCALIBRATED + +#define SENSOR_ACCELEROMETER 1 +#define SENSOR_MAGNETOMETER 2 +#define SENSOR_GYRO 4 +#define SENSOR_MAGNETOMETER_UNCALIBRATED 3 +#define SENSOR_GYRO_UNCALIBRATED 5 +#define SENSOR_PROXIMITY 6 +#define SENSOR_LIGHT 7 + +ExitHandler do_exit; +volatile sig_atomic_t re_init_sensors = 0; + +namespace { + +void sigpipe_handler(int sig) { + LOGE("SIGPIPE received"); + re_init_sensors = true; +} + +void sensor_loop() { + LOG("*** sensor loop"); + + uint64_t frame = 0; + bool low_power_mode = false; + + while (!do_exit) { + SubMaster sm({"deviceState"}); + PubMaster pm({"sensorEvents"}); + + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // required + struct sensor_t const* list; + int count = module->get_sensors_list(module, &list); + LOG("%d sensors found", count); + + if (getenv("SENSOR_TEST")) { + exit(count); + } + + for (int i = 0; i < count; i++) { + LOGD("sensor %4d: %4d %60s %d-%ld us", i, list[i].handle, list[i].name, list[i].minDelay, list[i].maxDelay); + } + + std::set sensor_types = { + SENSOR_TYPE_ACCELEROMETER, + SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED, + SENSOR_TYPE_MAGNETIC_FIELD, + SENSOR_TYPE_GYROSCOPE_UNCALIBRATED, + SENSOR_TYPE_GYROSCOPE, + SENSOR_TYPE_PROXIMITY, + SENSOR_TYPE_LIGHT, + }; + + std::map sensors = { + {SENSOR_GYRO_UNCALIBRATED, ms2ns(10)}, + {SENSOR_MAGNETOMETER_UNCALIBRATED, ms2ns(100)}, + {SENSOR_ACCELEROMETER, ms2ns(10)}, + {SENSOR_GYRO, ms2ns(10)}, + {SENSOR_MAGNETOMETER, ms2ns(100)}, + {SENSOR_PROXIMITY, ms2ns(100)}, + {SENSOR_LIGHT, ms2ns(100)} + }; + + // sensors needed while offroad + std::set offroad_sensors = { + SENSOR_LIGHT, + SENSOR_ACCELEROMETER, + SENSOR_GYRO_UNCALIBRATED, + }; + + // init all the sensors + for (auto &s : sensors) { + device->activate(device, s.first, 0); + device->activate(device, s.first, 1); + device->setDelay(device, s.first, s.second); + } + + // TODO: why is this 16? + static const size_t numEvents = 16; + sensors_event_t buffer[numEvents]; + + while (!do_exit) { + int n = device->poll(device, buffer, numEvents); + if (n == 0) continue; + if (n < 0) { + LOG("sensor_loop poll failed: %d", n); + continue; + } + + int log_events = 0; + for (int i=0; i < n; i++) { + if (sensor_types.find(buffer[i].type) != sensor_types.end()) { + log_events++; + } + } + + MessageBuilder msg; + auto sensor_events = msg.initEvent().initSensorEvents(log_events); + + int log_i = 0; + for (int i = 0; i < n; i++) { + + const sensors_event_t& data = buffer[i]; + + if (sensor_types.find(data.type) == sensor_types.end()) { + continue; + } + + auto log_event = sensor_events[log_i]; + log_event.setSource(cereal::SensorEventData::SensorSource::ANDROID); + log_event.setVersion(data.version); + log_event.setSensor(data.sensor); + log_event.setType(data.type); + log_event.setTimestamp(data.timestamp); + + switch (data.type) { + case SENSOR_TYPE_ACCELEROMETER: { + auto svec = log_event.initAcceleration(); + svec.setV(data.acceleration.v); + svec.setStatus(data.acceleration.status); + break; + } + case SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED: { + auto svec = log_event.initMagneticUncalibrated(); + // assuming the uncalib and bias floats are contiguous in memory + kj::ArrayPtr vs(&data.uncalibrated_magnetic.uncalib[0], 6); + svec.setV(vs); + break; + } + case SENSOR_TYPE_MAGNETIC_FIELD: { + auto svec = log_event.initMagnetic(); + svec.setV(data.magnetic.v); + svec.setStatus(data.magnetic.status); + break; + } + case SENSOR_TYPE_GYROSCOPE_UNCALIBRATED: { + auto svec = log_event.initGyroUncalibrated(); + // assuming the uncalib and bias floats are contiguous in memory + kj::ArrayPtr vs(&data.uncalibrated_gyro.uncalib[0], 6); + svec.setV(vs); + break; + } + case SENSOR_TYPE_GYROSCOPE: { + auto svec = log_event.initGyro(); + svec.setV(data.gyro.v); + svec.setStatus(data.gyro.status); + break; + } + case SENSOR_TYPE_PROXIMITY: { + log_event.setProximity(data.distance); + break; + } + case SENSOR_TYPE_LIGHT: + log_event.setLight(data.light); + break; + } + + log_i++; + } + + pm.send("sensorEvents", msg); + + if (re_init_sensors) { + LOGE("Resetting sensors"); + re_init_sensors = false; + break; + } + + // Check whether to go into low power mode at 5Hz + if (frame % 20 == 0) { + sm.update(0); + bool offroad = !sm["deviceState"].getDeviceState().getStarted(); + if (low_power_mode != offroad) { + for (auto &s : sensors) { + device->activate(device, s.first, 0); + if (!offroad || offroad_sensors.find(s.first) != offroad_sensors.end()) { + device->activate(device, s.first, 1); + } + } + low_power_mode = offroad; + } + } + + frame++; + } + sensors_close(device); + } +} + +}// Namespace end + +int main(int argc, char *argv[]) { + setpriority(PRIO_PROCESS, 0, -18); + signal(SIGPIPE, (sighandler_t)sigpipe_handler); + + sensor_loop(); + + return 0; +} diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index 1befb69aa4e8c7..0028371e81313c 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -21,8 +21,13 @@ from tools.lib.framereader import FrameReader from tools.lib.logreader import LogReader -TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36" +TICI_TEST_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36" +EON_TEST_ROUTE = "303055c0002aefd1|2021-11-22--18-36-32" SEGMENT = 0 +if TICI: + TEST_ROUTE = TICI_TEST_ROUTE +else: + TEST_ROUTE = EON_TEST_ROUTE SEND_EXTRA_INPUTS = bool(os.getenv("SEND_EXTRA_INPUTS", "0")) diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 1b518ddb217122..f2f76299f2b973 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -21,23 +21,44 @@ umount /data/safe_staging/merged/ || true sudo umount /data/safe_staging/merged/ || true export KEYS_PARAM_PATH="/data/params/d/GithubSshKeys" -export KEYS_PATH="/usr/comma/setup_keys" -export CONTINUE_PATH="/data/continue.sh" - -if ! grep -F "$KEYS_PATH" /etc/ssh/sshd_config; then - echo "setting up keys" - sudo mount -o rw,remount / - sudo systemctl enable ssh - sudo sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /etc/ssh/sshd_config - sudo mount -o ro,remount / +if [ -f "/EON" ]; then + export KEYS_PATH="/data/data/com.termux/files/home/setup_keys" + export CONTINUE_PATH="/data/data/com.termux/files/continue.sh" + + if ! grep -F "$KEYS_PATH" /usr/etc/ssh/sshd_config; then + echo "setting up keys" + mount -o rw,remount /system + sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /usr/etc/ssh/sshd_config + mount -o ro,remount /system + fi + + # these can get pretty big + rm -rf /data/core + rm -rf /data/neoupdate + rm -rf /data/safe_staging +else + export KEYS_PATH="/usr/comma/setup_keys" + export CONTINUE_PATH="/data/continue.sh" + + if ! grep -F "$KEYS_PATH" /etc/ssh/sshd_config; then + echo "setting up keys" + sudo mount -o rw,remount / + sudo systemctl enable ssh + sudo sed -i "s,$KEYS_PARAM_PATH,$KEYS_PATH," /etc/ssh/sshd_config + sudo mount -o ro,remount / + fi fi tee $CONTINUE_PATH << EOF #!/usr/bin/bash while true; do - if ! sudo systemctl is-active -q ssh; then - sudo systemctl start ssh + if [ -f /EON ]; then + setprop persist.neos.ssh 1 + else + if ! sudo systemctl is-active -q ssh; then + sudo systemctl start ssh + fi fi sleep 10s done diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index c8c1a34375a196..5a86f1da91f301 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -15,25 +15,25 @@ from common.timeout import Timeout from common.params import Params from selfdrive.controls.lib.events import EVENTS, ET +from selfdrive.hardware import EON, TICI from selfdrive.loggerd.config import ROOT from selfdrive.test.helpers import set_params_enabled, release_only from tools.lib.logreader import LogReader # Baseline CPU usage by process PROCS = { - "selfdrive.controls.controlsd": 31.0, - "./loggerd": 70.0, - "./camerad": 41.0, + "selfdrive.controls.controlsd": 55.0, + "./loggerd": 45.0, "./locationd": 9.1, "selfdrive.controls.plannerd": 11.7, "./_ui": 18.4, "selfdrive.locationd.paramsd": 9.0, "./_sensord": 6.17, - "selfdrive.controls.radard": 4.5, + "selfdrive.controls.radard": 7.0, "./_modeld": 4.48, "./boardd": 3.63, - "./_dmonitoringmodeld": 10.0, - "selfdrive.thermald.thermald": 3.87, + "./_dmonitoringmodeld": 2.67, + "selfdrive.thermald.thermald": 5.36, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, "selfdrive.monitoring.dmonitoringd": 1.90, @@ -45,6 +45,26 @@ "./logcatd": 0, } +if EON: + PROCS.update({ + "selfdrive.hardware.eon.androidd": 0.4, + "selfdrive.hardware.eon.shutdownd": 0.4, + }) + +if TICI: + PROCS.update({ + "./loggerd": 70.0, + "selfdrive.controls.controlsd": 31.0, + "./camerad": 41.0, + "./_ui": 33.0, + "selfdrive.controls.plannerd": 11.7, + "./_dmonitoringmodeld": 10.0, + "selfdrive.locationd.paramsd": 5.0, + "selfdrive.controls.radard": 4.5, + "selfdrive.thermald.thermald": 3.87, + }) + + TIMINGS = { # rtols: max/min, rsd "can": [2.5, 0.35], @@ -61,8 +81,15 @@ "modelV2": [2.5, 0.35], "driverState": [2.5, 0.35], "liveLocationKalman": [2.5, 0.35], - "wideRoadCameraState": [1.5, 0.35], } +if EON: + TIMINGS.update({ + "roadCameraState": [2.5, 0.45], + }) +if TICI: + TIMINGS.update({ + "wideRoadCameraState": [1.5, 0.35], + }) def cputime_total(ct): @@ -204,10 +231,12 @@ def test_model_execution_timings(self): result += "----------------- Model Timing -----------------\n" result += "------------------------------------------------\n" # TODO: this went up when plannerd cpu usage increased, why? - cfgs = [ - ("modelV2", 0.050, 0.036), - ("driverState", 0.050, 0.026), - ] + cfgs = [("driverState", 0.028, 0.026)] + if EON: + cfgs += [("modelV2", 0.045, 0.04)] + else: + cfgs += [("modelV2", 0.038, 0.036), ("driverState", 0.028, 0.026)] + for (s, instant_max, avg_max) in cfgs: ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.lr if m.which() == s] self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") diff --git a/selfdrive/thermald/fan_controller.py b/selfdrive/thermald/fan_controller.py index b1c7013297f5c4..7bd4d151346095 100644 --- a/selfdrive/thermald/fan_controller.py +++ b/selfdrive/thermald/fan_controller.py @@ -1,6 +1,8 @@ #!/usr/bin/env python3 -from abc import ABC, abstractmethod +import os +from smbus2 import SMBus +from abc import ABC, abstractmethod from common.realtime import DT_TRML from common.numpy_fast import interp from selfdrive.swaglog import cloudlog @@ -12,6 +14,69 @@ def update(self, max_cpu_temp: float, ignition: bool) -> int: pass +class EonFanController(BaseFanController): + # Temp thresholds to control fan speed - high hysteresis + TEMP_THRS_H = [50., 65., 80., 10000] + # Temp thresholds to control fan speed - low hysteresis + TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] + # Fan speed options + FAN_SPEEDS = [0, 16384, 32768, 65535] + + def __init__(self) -> None: + super().__init__() + cloudlog.info("Setting up EON fan handler") + + self.fan_speed = -1 + self.setup_eon_fan() + + def setup_eon_fan(self) -> None: + os.system("echo 2 > /sys/module/dwc3_msm/parameters/otg_switch") + + def set_eon_fan(self, speed: int) -> None: + if self.fan_speed != speed: + # FIXME: this is such an ugly hack to get the right index + val = speed // 16384 + + bus = SMBus(7, force=True) + try: + i = [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10][val] + bus.write_i2c_block_data(0x3d, 0, [i]) + except OSError: + # tusb320 + if val == 0: + bus.write_i2c_block_data(0x67, 0xa, [0]) + else: + bus.write_i2c_block_data(0x67, 0xa, [0x20]) + bus.write_i2c_block_data(0x67, 0x8, [(val - 1) << 6]) + bus.close() + self.fan_speed = speed + + def update(self, max_cpu_temp: float, ignition: bool) -> int: + new_speed_h = next(speed for speed, temp_h in zip(self.FAN_SPEEDS, self.TEMP_THRS_H) if temp_h > max_cpu_temp) + new_speed_l = next(speed for speed, temp_l in zip(self.FAN_SPEEDS, self.TEMP_THRS_L) if temp_l > max_cpu_temp) + + if new_speed_h > self.fan_speed: + self.set_eon_fan(new_speed_h) + elif new_speed_l < self.fan_speed: + self.set_eon_fan(new_speed_l) + + return self.fan_speed + + +class UnoFanController(BaseFanController): + def __init__(self) -> None: + super().__init__() + cloudlog.info("Setting up UNO fan handler") + + def update(self, max_cpu_temp: float, ignition: bool) -> int: + new_speed = int(interp(max_cpu_temp, [40.0, 80.0], [0, 80])) + + if not ignition: + new_speed = min(30, new_speed) + + return new_speed + + class TiciFanController(BaseFanController): def __init__(self) -> None: super().__init__() diff --git a/selfdrive/thermald/tests/test_fan_controller.py b/selfdrive/thermald/tests/test_fan_controller.py index 857866f64eac60..8865b1f98bcf2a 100755 --- a/selfdrive/thermald/tests/test_fan_controller.py +++ b/selfdrive/thermald/tests/test_fan_controller.py @@ -1,11 +1,13 @@ #!/usr/bin/env python3 import unittest -from unittest.mock import Mock, patch +from unittest.mock import Mock, MagicMock, patch from parameterized import parameterized -from selfdrive.thermald.fan_controller import TiciFanController +with patch("smbus2.SMBus", new=MagicMock()): + from selfdrive.thermald.fan_controller import EonFanController, UnoFanController, TiciFanController -ALL_CONTROLLERS = [(TiciFanController,)] +ALL_CONTROLLERS = [(EonFanController, ), (UnoFanController,), (TiciFanController,)] +GEN2_CONTROLLERS = [(UnoFanController,), (TiciFanController,)] def patched_controller(controller_class): with patch("os.system", new=Mock()): @@ -26,7 +28,7 @@ def test_hot_onroad(self, controller_class): self.wind_up(controller) self.assertGreaterEqual(controller.update(max_cpu_temp=100, ignition=True), 70) - @parameterized.expand(ALL_CONTROLLERS) + @parameterized.expand(GEN2_CONTROLLERS) def test_offroad_limits(self, controller_class): controller = patched_controller(controller_class) self.wind_up(controller) @@ -38,7 +40,7 @@ def test_no_fan_wear(self, controller_class): self.wind_down(controller) self.assertEqual(controller.update(max_cpu_temp=10, ignition=False), 0) - @parameterized.expand(ALL_CONTROLLERS) + @parameterized.expand(GEN2_CONTROLLERS) def test_limited(self, controller_class): controller = patched_controller(controller_class) self.wind_up(controller, ignition=True) diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index f959c7c4d800bf..2fbf48d1708bc0 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -17,12 +17,12 @@ from common.params import Params from common.realtime import DT_TRML, sec_since_boot from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.hardware import HARDWARE, TICI +from selfdrive.hardware import EON, HARDWARE, PC, TICI from selfdrive.loggerd.config import get_available_percent from selfdrive.statsd import statlog from selfdrive.swaglog import cloudlog from selfdrive.thermald.power_monitoring import PowerMonitoring -from selfdrive.thermald.fan_controller import TiciFanController +from selfdrive.thermald.fan_controller import EonFanController, UnoFanController, TiciFanController from selfdrive.version import terms_version, training_version ThermalStatus = log.DeviceState.ThermalStatus @@ -174,6 +174,7 @@ def thermald_thread(end_event, hw_queue): started_ts = None started_seen = False thermal_status = ThermalStatus.green + usb_power = True last_hw_state = HardwareState( network_type=NetworkType.none, @@ -188,6 +189,7 @@ def thermald_thread(end_event, hw_queue): temp_filter = FirstOrderFilter(0., TEMP_TAU, DT_TRML) should_start_prev = False in_car = False + is_uno = False engaged_prev = False params = Params() @@ -214,11 +216,18 @@ def thermald_thread(end_event, hw_queue): pandaState = pandaStates[0] in_car = pandaState.harnessStatus != log.PandaState.HarnessStatus.notConnected + usb_power = peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client # Setup fan handler on first connect to panda if fan_controller is None and peripheralState.pandaType != log.PandaState.PandaType.unknown: + is_uno = peripheralState.pandaType == log.PandaState.PandaType.uno + if TICI: fan_controller = TiciFanController() + elif is_uno or PC: + fan_controller = UnoFanController() + else: + fan_controller = EonFanController() try: last_hw_state = hw_queue.get_nowait() @@ -371,6 +380,9 @@ def thermald_thread(end_event, hw_queue): msg.deviceState.thermalStatus = thermal_status pm.send("deviceState", msg) + if EON and not is_uno: + set_offroad_alert_if_changed("Offroad_ChargeDisabled", (not usb_power)) + should_start_prev = should_start startup_conditions_prev = startup_conditions.copy() @@ -397,6 +409,9 @@ def thermald_thread(end_event, hw_queue): # report to server once every 10 minutes if (count % int(600. / DT_TRML)) == 0: + if EON and started_ts is None and msg.deviceState.memoryUsagePercent > 40: + cloudlog.event("High offroad memory usage", mem=msg.deviceState.memoryUsagePercent) + cloudlog.event("STATUS_PACKET", count=count, pandaStates=[strip_deprecated_keys(p.to_dict()) for p in pandaStates], diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 1ea13d556417eb..e1a19d5ffce2d2 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -7,6 +7,9 @@ base_libs = [gpucommon, common, messaging, cereal, visionipc, transformations, ' maps = arch in ['larch64', 'x86_64'] +if arch == 'aarch64': + base_libs += ['log', 'utils', 'gui', 'ui', 'CB', 'gsl', 'adreno_utils', 'cutils', 'uuid'] + if maps and arch == 'x86_64': rpath = [Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath] qt_env["RPATH"] += rpath @@ -19,7 +22,10 @@ widgets_src = ["ui.cc", "qt/util.cc", "qt/widgets/input.cc", "qt/widgets/drive_s "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc", "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", "qt/api.cc", - "qt/request_repeater.cc", "qt/qt_window.cc", "qt/offroad/networking.cc", "qt/offroad/wifiManager.cc"] + "qt/request_repeater.cc", "qt/qt_window.cc"] + +if arch != 'aarch64': + widgets_src += ["qt/offroad/networking.cc", "qt/offroad/wifiManager.cc"] qt_env['CPPDEFINES'] = [] if maps: @@ -57,7 +63,7 @@ qt_env.Program("_ui", qt_src + [asset_obj], LIBS=qt_libs) # setup and factory resetter -if GetOption('extras'): +if arch != 'aarch64' and GetOption('extras'): qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs) qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj], LIBS=qt_libs + ['curl', 'common', 'json11']) @@ -74,8 +80,8 @@ if GetOption('extras'): senv = qt_env.Clone() senv['LINKFLAGS'].append('-Wl,-strip-debug') - release = "release3" - dashcam = "dashcam3" + release = "release3" if arch == 'larch64' else "release2" + dashcam = "dashcam3" if arch == 'larch64' else "dashcam" installers = [ ("openpilot", release), ("openpilot_test", f"{release}-staging"), diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index 3588026ba68724..5366a0eac685cd 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -25,7 +25,12 @@ const std::string GIT_URL = get_str("https://github.com/commaai/openpilot.git" " const std::string BRANCH_STR = get_str(BRANCH "? "); #define GIT_SSH_URL "git@github.com:commaai/openpilot.git" -#define CONTINUE_PATH "/data/continue.sh" + +#ifdef QCOM + #define CONTINUE_PATH "/data/data/com.termux/files/continue.sh" +#else + #define CONTINUE_PATH "/data/continue.sh" +#endif const QString CACHE_PATH = "/data/openpilot.cache"; @@ -207,8 +212,12 @@ void Installer::cloneFinished(int exitCode, QProcess::ExitStatus exitStatus) { run("chmod +x /data/continue.sh.new"); run("mv /data/continue.sh.new " CONTINUE_PATH); +#ifdef QCOM + QTimer::singleShot(100, &QCoreApplication::quit); +#else // wait for the installed software's UI to take over QTimer::singleShot(60 * 1000, &QCoreApplication::quit); +#endif } int main(int argc, char *argv[]) { diff --git a/selfdrive/ui/main.cc b/selfdrive/ui/main.cc index cffa4596225227..8477bc8966d4f5 100644 --- a/selfdrive/ui/main.cc +++ b/selfdrive/ui/main.cc @@ -1,6 +1,7 @@ #include #include +#include #include "selfdrive/hardware/hw.h" #include "selfdrive/ui/qt/qt_window.h" @@ -13,6 +14,12 @@ int main(int argc, char *argv[]) { qInstallMessageHandler(swagLogMessageHandler); initApp(argc, argv); + if (Hardware::EON()) { + QSslConfiguration ssl = QSslConfiguration::defaultConfiguration(); + ssl.setCaCertificates(QSslCertificate::fromPath("/usr/etc/tls/cert.pem")); + QSslConfiguration::setDefaultConfiguration(ssl); + } + QApplication a(argc, argv); MainWindow w; setMainWindow(&w); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 6525bd7e236feb..4dd22dac8adc18 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -6,7 +6,9 @@ #include +#ifndef QCOM #include "selfdrive/ui/qt/offroad/networking.h" +#endif #ifdef ENABLE_MAPS #include "selfdrive/ui/qt/maps/map_settings.h" @@ -300,8 +302,57 @@ void SoftwarePanel::updateLabels() { osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed()); } +C2NetworkPanel::C2NetworkPanel(QWidget *parent) : QWidget(parent) { + QVBoxLayout *layout = new QVBoxLayout(this); + layout->setContentsMargins(50, 0, 50, 0); + + ListWidget *list = new ListWidget(); + list->setSpacing(30); + // wifi + tethering buttons +#ifdef QCOM + auto wifiBtn = new ButtonControl("Wi-Fi Settings", "OPEN"); + QObject::connect(wifiBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_wifi(); }); + list->addItem(wifiBtn); + + auto tetheringBtn = new ButtonControl("Tethering Settings", "OPEN"); + QObject::connect(tetheringBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_tethering(); }); + list->addItem(tetheringBtn); +#endif + ipaddress = new LabelControl("IP Address", ""); + list->addItem(ipaddress); + + // SSH key management + list->addItem(new SshToggle()); + list->addItem(new SshControl()); + layout->addWidget(list); + layout->addStretch(1); +} + +void C2NetworkPanel::showEvent(QShowEvent *event) { + ipaddress->setText(getIPAddress()); +} + +QString C2NetworkPanel::getIPAddress() { + std::string result = util::check_output("ifconfig wlan0"); + if (result.empty()) return ""; + + const std::string inetaddrr = "inet addr:"; + std::string::size_type begin = result.find(inetaddrr); + if (begin == std::string::npos) return ""; + + begin += inetaddrr.length(); + std::string::size_type end = result.find(' ', begin); + if (end == std::string::npos) return ""; + + return result.substr(begin, end - begin).c_str(); +} + QWidget *network_panel(QWidget *parent) { +#ifdef QCOM + return new C2NetworkPanel(parent); +#else return new Networking(parent); +#endif } void SettingsWindow::showEvent(QShowEvent *event) { @@ -418,3 +469,9 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { } )"); } + +void SettingsWindow::hideEvent(QHideEvent *event) { +#ifdef QCOM + HardwareEon::close_activities(); +#endif +} diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 160f10f99ffcd9..c3acf3d94a9714 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -19,6 +19,7 @@ class SettingsWindow : public QFrame { explicit SettingsWindow(QWidget *parent = 0); protected: + void hideEvent(QHideEvent *event) override; void showEvent(QShowEvent *event) override; signals: @@ -75,3 +76,14 @@ class SoftwarePanel : public ListWidget { Params params; QFileSystemWatcher *fs_watch; }; + +class C2NetworkPanel: public QWidget { + Q_OBJECT +public: + explicit C2NetworkPanel(QWidget* parent = nullptr); + +private: + void showEvent(QShowEvent *event) override; + QString getIPAddress(); + LabelControl *ipaddress; +}; diff --git a/selfdrive/ui/qt/setup/updater.cc b/selfdrive/ui/qt/setup/updater.cc index b906b5739da73f..6345d80db80b39 100644 --- a/selfdrive/ui/qt/setup/updater.cc +++ b/selfdrive/ui/qt/setup/updater.cc @@ -6,7 +6,10 @@ #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/setup/updater.h" + +#ifndef QCOM #include "selfdrive/ui/qt/offroad/networking.h" +#endif Updater::Updater(const QString &updater_path, const QString &manifest_path, QWidget *parent) : updater(updater_path), manifest(manifest_path), QStackedWidget(parent) { @@ -40,7 +43,11 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid QPushButton *connect = new QPushButton("Connect to Wi-Fi"); connect->setObjectName("navBtn"); QObject::connect(connect, &QPushButton::clicked, [=]() { +#ifndef QCOM setCurrentWidget(wifi); +#else + HardwareEon::launch_wifi(); +#endif }); hlayout->addWidget(connect); @@ -57,9 +64,11 @@ Updater::Updater(const QString &updater_path, const QString &manifest_path, QWid QVBoxLayout *layout = new QVBoxLayout(wifi); layout->setContentsMargins(100, 100, 100, 100); +#ifndef QCOM Networking *networking = new Networking(this, false); networking->setStyleSheet("Networking { background-color: #292929; border-radius: 13px; }"); layout->addWidget(networking, 1); +#endif QPushButton *back = new QPushButton("Back"); back->setObjectName("navBtn"); @@ -166,6 +175,20 @@ void Updater::updateFinished(int exitCode, QProcess::ExitStatus exitStatus) { } } +bool Updater::eventFilter(QObject *obj, QEvent *event) { +#ifdef QCOM + // filter out touches while in android activity + const static QSet filter_events({QEvent::MouseButtonPress, QEvent::MouseMove, QEvent::TouchBegin, QEvent::TouchUpdate, QEvent::TouchEnd}); + if (HardwareEon::launched_activity && filter_events.contains(event->type())) { + HardwareEon::check_activity(); + if (HardwareEon::launched_activity) { + return true; + } + } +#endif + return false; +} + int main(int argc, char *argv[]) { initApp(argc, argv); QApplication a(argc, argv); diff --git a/selfdrive/ui/qt/setup/updater.h b/selfdrive/ui/qt/setup/updater.h index ce46c0aabd089a..32aef43f5928aa 100644 --- a/selfdrive/ui/qt/setup/updater.h +++ b/selfdrive/ui/qt/setup/updater.h @@ -19,6 +19,8 @@ private slots: void updateFinished(int exitCode, QProcess::ExitStatus exitStatus); private: + bool eventFilter(QObject *obj, QEvent *event) override; + QProcess proc; QString updater, manifest; diff --git a/selfdrive/ui/qt/spinner_aarch64 b/selfdrive/ui/qt/spinner_aarch64 new file mode 100755 index 00000000000000..71a52bc9f1af55 Binary files /dev/null and b/selfdrive/ui/qt/spinner_aarch64 differ diff --git a/selfdrive/ui/qt/text_aarch64 b/selfdrive/ui/qt/text_aarch64 new file mode 100755 index 00000000000000..dbce56d59f3661 Binary files /dev/null and b/selfdrive/ui/qt/text_aarch64 differ diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index e38052ea599bf4..967b7d15d13f48 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -102,6 +102,9 @@ void initApp(int argc, char *argv[]) { #endif setQtSurfaceFormat(); + if (Hardware::EON()) { + QApplication::setAttribute(Qt::AA_ShareOpenGLContexts); + } } void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 3b773bd874d8af..cb94faedb18bc0 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -46,6 +46,10 @@ const char frame_fragment_shader[] = " float g = y - 0.344 * u - 0.714 * v;\n" " float b = y + 1.772 * u;\n" " colorOut = vec4(r, g, b, 1.0);\n" +#ifdef QCOM + " vec3 dz = vec3(0.0627f, 0.0627f, 0.0627f);\n" + " colorOut.rgb = ((vec3(1.0f, 1.0f, 1.0f) - dz) * colorOut.rgb / vec3(1.0f, 1.0f, 1.0f)) + dz;\n" +#endif "}\n"; const mat4 device_transform = {{ @@ -276,6 +280,25 @@ void CameraViewWidget::vipcThread() { VisionStreamType cur_stream_type = stream_type; std::unique_ptr vipc_client; + std::unique_ptr ctx; + std::unique_ptr surface; + std::unique_ptr gl_buffer; + + if (!Hardware::EON()) { + ctx = std::make_unique(); + ctx->setFormat(context()->format()); + ctx->setShareContext(context()); + ctx->create(); + assert(ctx->isValid()); + + surface = std::make_unique(); + surface->setFormat(ctx->format()); + surface->create(); + ctx->makeCurrent(surface.get()); + assert(QOpenGLContext::currentContext() == ctx.get()); + initializeOpenGLFunctions(); + } + while (!QThread::currentThread()->isInterruptionRequested()) { if (!vipc_client || cur_stream_type != stream_type) { cur_stream_type = stream_type; @@ -287,10 +310,50 @@ void CameraViewWidget::vipcThread() { QThread::msleep(100); continue; } + + if (!Hardware::EON()) { + gl_buffer.reset(new QOpenGLBuffer(QOpenGLBuffer::PixelUnpackBuffer)); + gl_buffer->create(); + gl_buffer->bind(); + gl_buffer->setUsagePattern(QOpenGLBuffer::StreamDraw); + gl_buffer->allocate(vipc_client->buffers[0].len); + } + emit vipcThreadConnected(vipc_client.get()); } if (VisionBuf *buf = vipc_client->recv(nullptr, 1000)) { + { + std::lock_guard lk(lock); + if (!Hardware::EON()) { + void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly); + + if (texture_buffer == nullptr) { + LOGE("gl_buffer->map returned nullptr"); + continue; + } + + memcpy(texture_buffer, buf->addr, buf->len); + gl_buffer->unmap(); + + // copy pixels from PBO to texture object + glBindTexture(GL_TEXTURE_2D, texture[buf->idx]->frame_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0); + glBindTexture(GL_TEXTURE_2D, 0); + assert(glGetError() == GL_NO_ERROR); + + wait_fence.reset(new WaitFence()); + + // Ensure the fence is in the GPU command queue, or waiting on it might block + // https://www.khronos.org/opengl/wiki/Sync_Object#Flushing_and_contexts + glFlush(); + } + latest_texture_id = buf->idx; + } + // Schedule update. update() will be invoked on the gui thread. + QMetaObject::invokeMethod(this, "update"); + + // TODO: remove later, it's only connected by DriverView. emit vipcThreadFrameReceived(buf); } } diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc index fb21f6f7afc620..76d5a39d44034d 100644 --- a/selfdrive/ui/qt/window.cc +++ b/selfdrive/ui/qt/window.cc @@ -85,6 +85,15 @@ bool MainWindow::eventFilter(QObject *obj, QEvent *event) { if (evts.contains(event->type())) { device.resetInteractiveTimout(); +#ifdef QCOM + // filter out touches while in android activity + if (HardwareEon::launched_activity) { + HardwareEon::check_activity(); + if (HardwareEon::launched_activity) { + return true; + } + } +#endif } return false; } diff --git a/selfdrive/ui/spinner b/selfdrive/ui/spinner index 6c8e533cc8d2e9..4a75ca25a4754e 100755 --- a/selfdrive/ui/spinner +++ b/selfdrive/ui/spinner @@ -1,6 +1,8 @@ #!/bin/sh -if [ -f /TICI ] && [ ! -f qt/spinner ]; then +if [ -f /EON ] && [ ! -f qt/spinner ]; then + cp qt/spinner_aarch64 qt/spinner +elif [ -f /TICI ] && [ ! -f qt/spinner ]; then cp qt/spinner_larch64 qt/spinner fi diff --git a/selfdrive/ui/text b/selfdrive/ui/text index 2577e3006bf14f..a7177c656f6937 100755 --- a/selfdrive/ui/text +++ b/selfdrive/ui/text @@ -1,6 +1,8 @@ #!/bin/sh -if [ -f /TICI ] && [ ! -f qt/text ]; then +if [ -f /EON ] && [ ! -f qt/text ]; then + cp qt/text_aarch64 qt/text +elif [ -f /TICI ] && [ ! -f qt/text ]; then cp qt/text_larch64 qt/text fi diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 0debb5ba04e0f0..37cafc071bdc2f 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -182,7 +182,17 @@ static void update_state(UIState *s) { } } } - if (Hardware::TICI() && sm.updated("wideRoadCameraState")) { + if (!Hardware::TICI() && sm.updated("roadCameraState")) { + auto camera_state = sm["roadCameraState"].getRoadCameraState(); + + float max_lines = Hardware::EON() ? 5408 : 1904; + float max_gain = Hardware::EON() ? 1.0: 10.0; + float max_ev = max_lines * max_gain; + + float ev = camera_state.getGain() * float(camera_state.getIntegLines()); + + scene.light_sensor = std::clamp(1.0 - (ev / max_ev), 0.0, 1.0); + } else if (Hardware::TICI() && sm.updated("wideRoadCameraState")) { auto camera_state = sm["wideRoadCameraState"].getWideRoadCameraState(); float max_lines = 1618; diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index e3415b8830aa48..49ced57ea2c7ef 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -24,8 +24,8 @@ typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; // TODO: this is also hardcoded in common/transformations/camera.py // TODO: choose based on frame input size -const float y_offset = 150.0; -const float ZOOM = 2912.8; +const float y_offset = Hardware::EON() ? 0.0 : 150.0; +const float ZOOM = Hardware::EON() ? 2138.5 : 2912.8; struct Alert { QString text1; diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 0988e409e19561..c287759d2c20db 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -37,7 +37,7 @@ from common.basedir import BASEDIR from common.markdown import parse_markdown from common.params import Params -from selfdrive.hardware import TICI, HARDWARE +from selfdrive.hardware import EON, TICI, HARDWARE from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.version import is_tested_branch @@ -287,6 +287,42 @@ def handle_agnos_update(wait_helper: WaitTimeHelper) -> None: set_offroad_alert("Offroad_NeosUpdate", False) +def handle_neos_update(wait_helper: WaitTimeHelper) -> None: + from selfdrive.hardware.eon.neos import download_neos_update + + cur_neos = HARDWARE.get_os_version() + updated_neos = run(["bash", "-c", r"unset REQUIRED_NEOS_VERSION && source launch_env.sh && \ + echo -n $REQUIRED_NEOS_VERSION"], OVERLAY_MERGED).strip() + + cloudlog.info(f"NEOS version check: {cur_neos} vs {updated_neos}") + if cur_neos == updated_neos: + return + + cloudlog.info(f"Beginning background download for NEOS {updated_neos}") + set_offroad_alert("Offroad_NeosUpdate", True) + + update_manifest = os.path.join(OVERLAY_MERGED, "selfdrive/hardware/eon/neos.json") + + neos_downloaded = False + start_time = time.monotonic() + # Try to download for one day + while not neos_downloaded and not wait_helper.shutdown and \ + (time.monotonic() - start_time < 60*60*24): + wait_helper.ready_event.clear() + try: + download_neos_update(update_manifest, cloudlog) + neos_downloaded = True + except Exception: + cloudlog.info("NEOS background download failed, retrying") + wait_helper.sleep(120) + + # If the download failed, we'll show the alert again when we retry + set_offroad_alert("Offroad_NeosUpdate", False) + if not neos_downloaded: + raise Exception("Failed to download NEOS update") + cloudlog.info(f"NEOS background download successful, took {time.monotonic() - start_time} seconds") + + def check_git_fetch_result(fetch_txt: str) -> bool: err_msg = "Failed to add the host to the list of known hosts (/data/data/com.termux/files/home/.ssh/known_hosts).\n" return len(fetch_txt) > 0 and (fetch_txt != err_msg) @@ -328,7 +364,9 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool: ] cloudlog.info("git reset success: %s", '\n'.join(r)) - if TICI: + if EON: + handle_neos_update(wait_helper) + elif TICI: handle_agnos_update(wait_helper) # Create the finalized, ready-to-swap update diff --git a/selfdrive/version.py b/selfdrive/version.py index 5517fe728ab84a..9b18edc4321e67 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -7,7 +7,7 @@ from common.basedir import BASEDIR from selfdrive.swaglog import cloudlog -TESTED_BRANCHES = ['devel', 'release3-staging', 'dashcam3-staging', 'release3', 'dashcam3'] +TESTED_BRANCHES = ['devel', 'release2-staging', 'release3-staging', 'dashcam-staging', 'release2', 'release3', 'dashcam'] training_version: bytes = b"0.2.0" terms_version: bytes = b"2" diff --git a/third_party/acados/aarch64/lib/libacados.so b/third_party/acados/aarch64/lib/libacados.so new file mode 100755 index 00000000000000..ef102d116a0992 Binary files /dev/null and b/third_party/acados/aarch64/lib/libacados.so differ diff --git a/third_party/acados/aarch64/lib/libblasfeo.so b/third_party/acados/aarch64/lib/libblasfeo.so new file mode 100755 index 00000000000000..5e3d2b13339caa Binary files /dev/null and b/third_party/acados/aarch64/lib/libblasfeo.so differ diff --git a/third_party/acados/aarch64/lib/libhpipm.so b/third_party/acados/aarch64/lib/libhpipm.so new file mode 100755 index 00000000000000..6916c9c7139493 Binary files /dev/null and b/third_party/acados/aarch64/lib/libhpipm.so differ diff --git a/third_party/acados/aarch64/lib/libqpOASES_e.so b/third_party/acados/aarch64/lib/libqpOASES_e.so new file mode 120000 index 00000000000000..14048625a1c2d3 --- /dev/null +++ b/third_party/acados/aarch64/lib/libqpOASES_e.so @@ -0,0 +1 @@ +libqpOASES_e.so.3.1 \ No newline at end of file diff --git a/third_party/acados/aarch64/lib/libqpOASES_e.so.3.1 b/third_party/acados/aarch64/lib/libqpOASES_e.so.3.1 new file mode 100755 index 00000000000000..98d8dbfcd1d34b Binary files /dev/null and b/third_party/acados/aarch64/lib/libqpOASES_e.so.3.1 differ diff --git a/third_party/acados/aarch64/t_renderer b/third_party/acados/aarch64/t_renderer new file mode 100755 index 00000000000000..dc3cdf554f793f Binary files /dev/null and b/third_party/acados/aarch64/t_renderer differ diff --git a/third_party/acados/build.sh b/third_party/acados/build.sh index 0b14a4cec9a01d..e0f603e682bb8a 100755 --- a/third_party/acados/build.sh +++ b/third_party/acados/build.sh @@ -7,6 +7,9 @@ BLAS_TARGET="X64_AUTOMATIC" if [ -f /TICI ]; then ARCHNAME="larch64" BLAS_TARGET="ARMV8A_ARM_CORTEX_A57" +elif [ -f /EON ]; then + ARCHNAME="aarch64" + BLAS_TARGET="ARMV8A_ARM_CORTEX_A57" fi if [ ! -d acados_repo/ ]; then @@ -37,7 +40,38 @@ rm -rf $DIR/../../pyextra/acados_template cp -r $DIR/acados_repo/interfaces/acados_template/acados_template $DIR/../../pyextra #pip3 install -e $DIR/acados/interfaces/acados_template +# hack to workaround no rpath on android +if [ -f /EON ]; then + pushd $INSTALL_DIR/lib + for lib in $(ls .); do + if ! readlink $lib; then + patchelf --set-soname $PWD/$lib $lib + + if [ "$lib" = "libacados.so" ]; then + for nlib in "libhpipm.so" "libblasfeo.so" "libqpOASES_e.so.3.1"; do + patchelf --replace-needed $nlib $PWD/$nlib $lib + done + fi + + if [ "$lib" = "libhpipm.so" ]; then + patchelf --replace-needed libblasfeo.so $PWD/libblasfeo.so $lib + fi + + # pad extra byte to workaround bionic linker bug + # https://android.googlesource.com/platform/bionic/+/93ce35434ca5af43a7449e289959543f0a2426fa%5E%21/#F0 + dd if=/dev/zero bs=1 count=1 >> $lib + fi + done + popd + + cd $DIR + git checkout $INSTALL_DIR/t_renderer +fi + # build tera -cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/ -cargo build --verbose --release -cp target/release/t_renderer $INSTALL_DIR/ +# build with commaai/termux-packages for NEOS +if [ ! -f /EON ]; then + cd $DIR/acados_repo/interfaces/acados_template/tera_renderer/ + cargo build --verbose --release + cp target/release/t_renderer $INSTALL_DIR/ +fi diff --git a/third_party/android_frameworks_native/get.txt b/third_party/android_frameworks_native/get.txt new file mode 100644 index 00000000000000..277bdcb6a8efe7 --- /dev/null +++ b/third_party/android_frameworks_native/get.txt @@ -0,0 +1,3 @@ +git clone https://github.com/CyanogenMod/android_frameworks_native.git && cd android_frameworks_native +git reset --hard b22bca465e55618a949d9cbdea665a1a3a831241 +cp -r include ~/one/third_party/android_frameworks_native/ diff --git a/third_party/android_frameworks_native/include/android/asset_manager.h b/third_party/android_frameworks_native/include/android/asset_manager.h new file mode 100644 index 00000000000000..d65483968e4673 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/asset_manager.h @@ -0,0 +1,215 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Asset + * @{ + */ + +/** + * @file asset_manager.h + */ + +#ifndef ANDROID_ASSET_MANAGER_H +#define ANDROID_ASSET_MANAGER_H + +#ifdef __cplusplus +extern "C" { +#endif + +struct AAssetManager; +/** + * {@link AAssetManager} provides access to an application's raw assets by + * creating {@link AAsset} objects. + * + * AAssetManager is a wrapper to the low-level native implementation + * of the java {@link AAssetManager}, a pointer can be obtained using + * AAssetManager_fromJava(). + * + * The asset hierarchy may be examined like a filesystem, using + * {@link AAssetDir} objects to peruse a single directory. + * + * A native {@link AAssetManager} pointer may be shared across multiple threads. + */ +typedef struct AAssetManager AAssetManager; + +struct AAssetDir; +/** + * {@link AAssetDir} provides access to a chunk of the asset hierarchy as if + * it were a single directory. The contents are populated by the + * {@link AAssetManager}. + * + * The list of files will be sorted in ascending order by ASCII value. + */ +typedef struct AAssetDir AAssetDir; + +struct AAsset; +/** + * {@link AAsset} provides access to a read-only asset. + * + * {@link AAsset} objects are NOT thread-safe, and should not be shared across + * threads. + */ +typedef struct AAsset AAsset; + +/** Available access modes for opening assets with {@link AAssetManager_open} */ +enum { + /** No specific information about how data will be accessed. **/ + AASSET_MODE_UNKNOWN = 0, + /** Read chunks, and seek forward and backward. */ + AASSET_MODE_RANDOM = 1, + /** Read sequentially, with an occasional forward seek. */ + AASSET_MODE_STREAMING = 2, + /** Caller plans to ask for a read-only buffer with all data. */ + AASSET_MODE_BUFFER = 3 +}; + + +/** + * Open the named directory within the asset hierarchy. The directory can then + * be inspected with the AAssetDir functions. To open the top-level directory, + * pass in "" as the dirName. + * + * The object returned here should be freed by calling AAssetDir_close(). + */ +AAssetDir* AAssetManager_openDir(AAssetManager* mgr, const char* dirName); + +/** + * Open an asset. + * + * The object returned here should be freed by calling AAsset_close(). + */ +AAsset* AAssetManager_open(AAssetManager* mgr, const char* filename, int mode); + +/** + * Iterate over the files in an asset directory. A NULL string is returned + * when all the file names have been returned. + * + * The returned file name is suitable for passing to AAssetManager_open(). + * + * The string returned here is owned by the AssetDir implementation and is not + * guaranteed to remain valid if any other calls are made on this AAssetDir + * instance. + */ +const char* AAssetDir_getNextFileName(AAssetDir* assetDir); + +/** + * Reset the iteration state of AAssetDir_getNextFileName() to the beginning. + */ +void AAssetDir_rewind(AAssetDir* assetDir); + +/** + * Close an opened AAssetDir, freeing any related resources. + */ +void AAssetDir_close(AAssetDir* assetDir); + +/** + * Attempt to read 'count' bytes of data from the current offset. + * + * Returns the number of bytes read, zero on EOF, or < 0 on error. + */ +int AAsset_read(AAsset* asset, void* buf, size_t count); + +/** + * Seek to the specified offset within the asset data. 'whence' uses the + * same constants as lseek()/fseek(). + * + * Returns the new position on success, or (off_t) -1 on error. + */ +off_t AAsset_seek(AAsset* asset, off_t offset, int whence); + +/** + * Seek to the specified offset within the asset data. 'whence' uses the + * same constants as lseek()/fseek(). + * + * Uses 64-bit data type for large files as opposed to the 32-bit type used + * by AAsset_seek. + * + * Returns the new position on success, or (off64_t) -1 on error. + */ +off64_t AAsset_seek64(AAsset* asset, off64_t offset, int whence); + +/** + * Close the asset, freeing all associated resources. + */ +void AAsset_close(AAsset* asset); + +/** + * Get a pointer to a buffer holding the entire contents of the assset. + * + * Returns NULL on failure. + */ +const void* AAsset_getBuffer(AAsset* asset); + +/** + * Report the total size of the asset data. + */ +off_t AAsset_getLength(AAsset* asset); + +/** + * Report the total size of the asset data. Reports the size using a 64-bit + * number insted of 32-bit as AAsset_getLength. + */ +off64_t AAsset_getLength64(AAsset* asset); + +/** + * Report the total amount of asset data that can be read from the current position. + */ +off_t AAsset_getRemainingLength(AAsset* asset); + +/** + * Report the total amount of asset data that can be read from the current position. + * + * Uses a 64-bit number instead of a 32-bit number as AAsset_getRemainingLength does. + */ +off64_t AAsset_getRemainingLength64(AAsset* asset); + +/** + * Open a new file descriptor that can be used to read the asset data. If the + * start or length cannot be represented by a 32-bit number, it will be + * truncated. If the file is large, use AAsset_openFileDescriptor64 instead. + * + * Returns < 0 if direct fd access is not possible (for example, if the asset is + * compressed). + */ +int AAsset_openFileDescriptor(AAsset* asset, off_t* outStart, off_t* outLength); + +/** + * Open a new file descriptor that can be used to read the asset data. + * + * Uses a 64-bit number for the offset and length instead of 32-bit instead of + * as AAsset_openFileDescriptor does. + * + * Returns < 0 if direct fd access is not possible (for example, if the asset is + * compressed). + */ +int AAsset_openFileDescriptor64(AAsset* asset, off64_t* outStart, off64_t* outLength); + +/** + * Returns whether this asset's internal buffer is allocated in ordinary RAM (i.e. not + * mmapped). + */ +int AAsset_isAllocated(AAsset* asset); + + + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_ASSET_MANAGER_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/asset_manager_jni.h b/third_party/android_frameworks_native/include/android/asset_manager_jni.h new file mode 100644 index 00000000000000..dcee17e10f143b --- /dev/null +++ b/third_party/android_frameworks_native/include/android/asset_manager_jni.h @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Asset + * @{ + */ + +/** + * @file asset_manager_jni.h + */ + +#ifndef ANDROID_ASSET_MANAGER_JNI_H +#define ANDROID_ASSET_MANAGER_JNI_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Given a Dalvik AssetManager object, obtain the corresponding native AAssetManager + * object. Note that the caller is responsible for obtaining and holding a VM reference + * to the jobject to prevent its being garbage collected while the native object is + * in use. + */ +AAssetManager* AAssetManager_fromJava(JNIEnv* env, jobject assetManager); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_ASSET_MANAGER_JNI_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/bitmap.h b/third_party/android_frameworks_native/include/android/bitmap.h new file mode 100644 index 00000000000000..261e64fac9b825 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/bitmap.h @@ -0,0 +1,112 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Bitmap + * @{ + */ + +/** + * @file bitmap.h + */ + +#ifndef ANDROID_BITMAP_H +#define ANDROID_BITMAP_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** AndroidBitmap functions result code. */ +enum { + /** Operation was successful. */ + ANDROID_BITMAP_RESULT_SUCCESS = 0, + /** Bad parameter. */ + ANDROID_BITMAP_RESULT_BAD_PARAMETER = -1, + /** JNI exception occured. */ + ANDROID_BITMAP_RESULT_JNI_EXCEPTION = -2, + /** Allocation failed. */ + ANDROID_BITMAP_RESULT_ALLOCATION_FAILED = -3, +}; + +/** Backward compatibility: this macro used to be misspelled. */ +#define ANDROID_BITMAP_RESUT_SUCCESS ANDROID_BITMAP_RESULT_SUCCESS + +/** Bitmap pixel format. */ +enum AndroidBitmapFormat { + /** No format. */ + ANDROID_BITMAP_FORMAT_NONE = 0, + /** Red: 8 bits, Green: 8 bits, Blue: 8 bits, Alpha: 8 bits. **/ + ANDROID_BITMAP_FORMAT_RGBA_8888 = 1, + /** Red: 5 bits, Green: 6 bits, Blue: 5 bits. **/ + ANDROID_BITMAP_FORMAT_RGB_565 = 4, + /** Red: 4 bits, Green: 4 bits, Blue: 4 bits, Alpha: 4 bits. **/ + ANDROID_BITMAP_FORMAT_RGBA_4444 = 7, + /** Deprecated. */ + ANDROID_BITMAP_FORMAT_A_8 = 8, +}; + +/** Bitmap info, see AndroidBitmap_getInfo(). */ +typedef struct { + /** The bitmap width in pixels. */ + uint32_t width; + /** The bitmap height in pixels. */ + uint32_t height; + /** The number of byte per row. */ + uint32_t stride; + /** The bitmap pixel format. See {@link AndroidBitmapFormat} */ + int32_t format; + /** Unused. */ + uint32_t flags; // 0 for now +} AndroidBitmapInfo; + +/** + * Given a java bitmap object, fill out the AndroidBitmapInfo struct for it. + * If the call fails, the info parameter will be ignored. + */ +int AndroidBitmap_getInfo(JNIEnv* env, jobject jbitmap, + AndroidBitmapInfo* info); + +/** + * Given a java bitmap object, attempt to lock the pixel address. + * Locking will ensure that the memory for the pixels will not move + * until the unlockPixels call, and ensure that, if the pixels had been + * previously purged, they will have been restored. + * + * If this call succeeds, it must be balanced by a call to + * AndroidBitmap_unlockPixels, after which time the address of the pixels should + * no longer be used. + * + * If this succeeds, *addrPtr will be set to the pixel address. If the call + * fails, addrPtr will be ignored. + */ +int AndroidBitmap_lockPixels(JNIEnv* env, jobject jbitmap, void** addrPtr); + +/** + * Call this to balance a successful call to AndroidBitmap_lockPixels. + */ +int AndroidBitmap_unlockPixels(JNIEnv* env, jobject jbitmap); + +#ifdef __cplusplus +} +#endif + +#endif + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/configuration.h b/third_party/android_frameworks_native/include/android/configuration.h new file mode 100644 index 00000000000000..81f71a92cb05e2 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/configuration.h @@ -0,0 +1,708 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Configuration + * @{ + */ + +/** + * @file configuration.h + */ + +#ifndef ANDROID_CONFIGURATION_H +#define ANDROID_CONFIGURATION_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +struct AConfiguration; +/** + * {@link AConfiguration} is an opaque type used to get and set + * various subsystem configurations. + * + * A {@link AConfiguration} pointer can be obtained using: + * - AConfiguration_new() + * - AConfiguration_fromAssetManager() + */ +typedef struct AConfiguration AConfiguration; + + +/** + * Define flags and constants for various subsystem configurations. + */ +enum { + /** Orientation: not specified. */ + ACONFIGURATION_ORIENTATION_ANY = 0x0000, + /** + * Orientation: value corresponding to the + * port + * resource qualifier. + */ + ACONFIGURATION_ORIENTATION_PORT = 0x0001, + /** + * Orientation: value corresponding to the + * land + * resource qualifier. + */ + ACONFIGURATION_ORIENTATION_LAND = 0x0002, + /** @deprecated Not currently supported or used. */ + ACONFIGURATION_ORIENTATION_SQUARE = 0x0003, + + /** Touchscreen: not specified. */ + ACONFIGURATION_TOUCHSCREEN_ANY = 0x0000, + /** + * Touchscreen: value corresponding to the + * notouch + * resource qualifier. + */ + ACONFIGURATION_TOUCHSCREEN_NOTOUCH = 0x0001, + /** @deprecated Not currently supported or used. */ + ACONFIGURATION_TOUCHSCREEN_STYLUS = 0x0002, + /** + * Touchscreen: value corresponding to the + * finger + * resource qualifier. + */ + ACONFIGURATION_TOUCHSCREEN_FINGER = 0x0003, + + /** Density: default density. */ + ACONFIGURATION_DENSITY_DEFAULT = 0, + /** + * Density: value corresponding to the + * ldpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_LOW = 120, + /** + * Density: value corresponding to the + * mdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_MEDIUM = 160, + /** + * Density: value corresponding to the + * tvdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_TV = 213, + /** + * Density: value corresponding to the + * hdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_HIGH = 240, + /** + * Density: value corresponding to the + * xhdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_XHIGH = 320, + /** + * Density: value corresponding to the + * xxhdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_XXHIGH = 480, + /** + * Density: value corresponding to the + * xxxhdpi + * resource qualifier. + */ + ACONFIGURATION_DENSITY_XXXHIGH = 640, + /** Density: any density. */ + ACONFIGURATION_DENSITY_ANY = 0xfffe, + /** Density: no density specified. */ + ACONFIGURATION_DENSITY_NONE = 0xffff, + + /** Keyboard: not specified. */ + ACONFIGURATION_KEYBOARD_ANY = 0x0000, + /** + * Keyboard: value corresponding to the + * nokeys + * resource qualifier. + */ + ACONFIGURATION_KEYBOARD_NOKEYS = 0x0001, + /** + * Keyboard: value corresponding to the + * qwerty + * resource qualifier. + */ + ACONFIGURATION_KEYBOARD_QWERTY = 0x0002, + /** + * Keyboard: value corresponding to the + * 12key + * resource qualifier. + */ + ACONFIGURATION_KEYBOARD_12KEY = 0x0003, + + /** Navigation: not specified. */ + ACONFIGURATION_NAVIGATION_ANY = 0x0000, + /** + * Navigation: value corresponding to the + * nonav + * resource qualifier. + */ + ACONFIGURATION_NAVIGATION_NONAV = 0x0001, + /** + * Navigation: value corresponding to the + * dpad + * resource qualifier. + */ + ACONFIGURATION_NAVIGATION_DPAD = 0x0002, + /** + * Navigation: value corresponding to the + * trackball + * resource qualifier. + */ + ACONFIGURATION_NAVIGATION_TRACKBALL = 0x0003, + /** + * Navigation: value corresponding to the + * wheel + * resource qualifier. + */ + ACONFIGURATION_NAVIGATION_WHEEL = 0x0004, + + /** Keyboard availability: not specified. */ + ACONFIGURATION_KEYSHIDDEN_ANY = 0x0000, + /** + * Keyboard availability: value corresponding to the + * keysexposed + * resource qualifier. + */ + ACONFIGURATION_KEYSHIDDEN_NO = 0x0001, + /** + * Keyboard availability: value corresponding to the + * keyshidden + * resource qualifier. + */ + ACONFIGURATION_KEYSHIDDEN_YES = 0x0002, + /** + * Keyboard availability: value corresponding to the + * keyssoft + * resource qualifier. + */ + ACONFIGURATION_KEYSHIDDEN_SOFT = 0x0003, + + /** Navigation availability: not specified. */ + ACONFIGURATION_NAVHIDDEN_ANY = 0x0000, + /** + * Navigation availability: value corresponding to the + * navexposed + * resource qualifier. + */ + ACONFIGURATION_NAVHIDDEN_NO = 0x0001, + /** + * Navigation availability: value corresponding to the + * navhidden + * resource qualifier. + */ + ACONFIGURATION_NAVHIDDEN_YES = 0x0002, + + /** Screen size: not specified. */ + ACONFIGURATION_SCREENSIZE_ANY = 0x00, + /** + * Screen size: value indicating the screen is at least + * approximately 320x426 dp units, corresponding to the + * small + * resource qualifier. + */ + ACONFIGURATION_SCREENSIZE_SMALL = 0x01, + /** + * Screen size: value indicating the screen is at least + * approximately 320x470 dp units, corresponding to the + * normal + * resource qualifier. + */ + ACONFIGURATION_SCREENSIZE_NORMAL = 0x02, + /** + * Screen size: value indicating the screen is at least + * approximately 480x640 dp units, corresponding to the + * large + * resource qualifier. + */ + ACONFIGURATION_SCREENSIZE_LARGE = 0x03, + /** + * Screen size: value indicating the screen is at least + * approximately 720x960 dp units, corresponding to the + * xlarge + * resource qualifier. + */ + ACONFIGURATION_SCREENSIZE_XLARGE = 0x04, + + /** Screen layout: not specified. */ + ACONFIGURATION_SCREENLONG_ANY = 0x00, + /** + * Screen layout: value that corresponds to the + * notlong + * resource qualifier. + */ + ACONFIGURATION_SCREENLONG_NO = 0x1, + /** + * Screen layout: value that corresponds to the + * long + * resource qualifier. + */ + ACONFIGURATION_SCREENLONG_YES = 0x2, + + ACONFIGURATION_SCREENROUND_ANY = 0x00, + ACONFIGURATION_SCREENROUND_NO = 0x1, + ACONFIGURATION_SCREENROUND_YES = 0x2, + + /** UI mode: not specified. */ + ACONFIGURATION_UI_MODE_TYPE_ANY = 0x00, + /** + * UI mode: value that corresponds to + * no + * UI mode type resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_NORMAL = 0x01, + /** + * UI mode: value that corresponds to + * desk resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_DESK = 0x02, + /** + * UI mode: value that corresponds to + * car resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_CAR = 0x03, + /** + * UI mode: value that corresponds to + * television resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_TELEVISION = 0x04, + /** + * UI mode: value that corresponds to + * appliance resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_APPLIANCE = 0x05, + /** + * UI mode: value that corresponds to + * watch resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_TYPE_WATCH = 0x06, + + /** UI night mode: not specified.*/ + ACONFIGURATION_UI_MODE_NIGHT_ANY = 0x00, + /** + * UI night mode: value that corresponds to + * notnight resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_NIGHT_NO = 0x1, + /** + * UI night mode: value that corresponds to + * night resource qualifier specified. + */ + ACONFIGURATION_UI_MODE_NIGHT_YES = 0x2, + + /** Screen width DPI: not specified. */ + ACONFIGURATION_SCREEN_WIDTH_DP_ANY = 0x0000, + + /** Screen height DPI: not specified. */ + ACONFIGURATION_SCREEN_HEIGHT_DP_ANY = 0x0000, + + /** Smallest screen width DPI: not specified.*/ + ACONFIGURATION_SMALLEST_SCREEN_WIDTH_DP_ANY = 0x0000, + + /** Layout direction: not specified. */ + ACONFIGURATION_LAYOUTDIR_ANY = 0x00, + /** + * Layout direction: value that corresponds to + * ldltr resource qualifier specified. + */ + ACONFIGURATION_LAYOUTDIR_LTR = 0x01, + /** + * Layout direction: value that corresponds to + * ldrtl resource qualifier specified. + */ + ACONFIGURATION_LAYOUTDIR_RTL = 0x02, + + /** + * Bit mask for + * mcc + * configuration. + */ + ACONFIGURATION_MCC = 0x0001, + /** + * Bit mask for + * mnc + * configuration. + */ + ACONFIGURATION_MNC = 0x0002, + /** + * Bit mask for + * locale + * configuration. + */ + ACONFIGURATION_LOCALE = 0x0004, + /** + * Bit mask for + * touchscreen + * configuration. + */ + ACONFIGURATION_TOUCHSCREEN = 0x0008, + /** + * Bit mask for + * keyboard + * configuration. + */ + ACONFIGURATION_KEYBOARD = 0x0010, + /** + * Bit mask for + * keyboardHidden + * configuration. + */ + ACONFIGURATION_KEYBOARD_HIDDEN = 0x0020, + /** + * Bit mask for + * navigation + * configuration. + */ + ACONFIGURATION_NAVIGATION = 0x0040, + /** + * Bit mask for + * orientation + * configuration. + */ + ACONFIGURATION_ORIENTATION = 0x0080, + /** + * Bit mask for + * density + * configuration. + */ + ACONFIGURATION_DENSITY = 0x0100, + /** + * Bit mask for + * screen size + * configuration. + */ + ACONFIGURATION_SCREEN_SIZE = 0x0200, + /** + * Bit mask for + * platform version + * configuration. + */ + ACONFIGURATION_VERSION = 0x0400, + /** + * Bit mask for screen layout configuration. + */ + ACONFIGURATION_SCREEN_LAYOUT = 0x0800, + /** + * Bit mask for + * ui mode + * configuration. + */ + ACONFIGURATION_UI_MODE = 0x1000, + /** + * Bit mask for + * smallest screen width + * configuration. + */ + ACONFIGURATION_SMALLEST_SCREEN_SIZE = 0x2000, + /** + * Bit mask for + * layout direction + * configuration. + */ + ACONFIGURATION_LAYOUTDIR = 0x4000, + ACONFIGURATION_SCREEN_ROUND = 0x8000, + /** + * Constant used to to represent MNC (Mobile Network Code) zero. + * 0 cannot be used, since it is used to represent an undefined MNC. + */ + ACONFIGURATION_MNC_ZERO = 0xffff, +}; + +/** + * Create a new AConfiguration, initialized with no values set. + */ +AConfiguration* AConfiguration_new(); + +/** + * Free an AConfiguration that was previously created with + * AConfiguration_new(). + */ +void AConfiguration_delete(AConfiguration* config); + +/** + * Create and return a new AConfiguration based on the current configuration in + * use in the given {@link AAssetManager}. + */ +void AConfiguration_fromAssetManager(AConfiguration* out, AAssetManager* am); + +/** + * Copy the contents of 'src' to 'dest'. + */ +void AConfiguration_copy(AConfiguration* dest, AConfiguration* src); + +/** + * Return the current MCC set in the configuration. 0 if not set. + */ +int32_t AConfiguration_getMcc(AConfiguration* config); + +/** + * Set the current MCC in the configuration. 0 to clear. + */ +void AConfiguration_setMcc(AConfiguration* config, int32_t mcc); + +/** + * Return the current MNC set in the configuration. 0 if not set. + */ +int32_t AConfiguration_getMnc(AConfiguration* config); + +/** + * Set the current MNC in the configuration. 0 to clear. + */ +void AConfiguration_setMnc(AConfiguration* config, int32_t mnc); + +/** + * Return the current language code set in the configuration. The output will + * be filled with an array of two characters. They are not 0-terminated. If + * a language is not set, they will be 0. + */ +void AConfiguration_getLanguage(AConfiguration* config, char* outLanguage); + +/** + * Set the current language code in the configuration, from the first two + * characters in the string. + */ +void AConfiguration_setLanguage(AConfiguration* config, const char* language); + +/** + * Return the current country code set in the configuration. The output will + * be filled with an array of two characters. They are not 0-terminated. If + * a country is not set, they will be 0. + */ +void AConfiguration_getCountry(AConfiguration* config, char* outCountry); + +/** + * Set the current country code in the configuration, from the first two + * characters in the string. + */ +void AConfiguration_setCountry(AConfiguration* config, const char* country); + +/** + * Return the current ACONFIGURATION_ORIENTATION_* set in the configuration. + */ +int32_t AConfiguration_getOrientation(AConfiguration* config); + +/** + * Set the current orientation in the configuration. + */ +void AConfiguration_setOrientation(AConfiguration* config, int32_t orientation); + +/** + * Return the current ACONFIGURATION_TOUCHSCREEN_* set in the configuration. + */ +int32_t AConfiguration_getTouchscreen(AConfiguration* config); + +/** + * Set the current touchscreen in the configuration. + */ +void AConfiguration_setTouchscreen(AConfiguration* config, int32_t touchscreen); + +/** + * Return the current ACONFIGURATION_DENSITY_* set in the configuration. + */ +int32_t AConfiguration_getDensity(AConfiguration* config); + +/** + * Set the current density in the configuration. + */ +void AConfiguration_setDensity(AConfiguration* config, int32_t density); + +/** + * Return the current ACONFIGURATION_KEYBOARD_* set in the configuration. + */ +int32_t AConfiguration_getKeyboard(AConfiguration* config); + +/** + * Set the current keyboard in the configuration. + */ +void AConfiguration_setKeyboard(AConfiguration* config, int32_t keyboard); + +/** + * Return the current ACONFIGURATION_NAVIGATION_* set in the configuration. + */ +int32_t AConfiguration_getNavigation(AConfiguration* config); + +/** + * Set the current navigation in the configuration. + */ +void AConfiguration_setNavigation(AConfiguration* config, int32_t navigation); + +/** + * Return the current ACONFIGURATION_KEYSHIDDEN_* set in the configuration. + */ +int32_t AConfiguration_getKeysHidden(AConfiguration* config); + +/** + * Set the current keys hidden in the configuration. + */ +void AConfiguration_setKeysHidden(AConfiguration* config, int32_t keysHidden); + +/** + * Return the current ACONFIGURATION_NAVHIDDEN_* set in the configuration. + */ +int32_t AConfiguration_getNavHidden(AConfiguration* config); + +/** + * Set the current nav hidden in the configuration. + */ +void AConfiguration_setNavHidden(AConfiguration* config, int32_t navHidden); + +/** + * Return the current SDK (API) version set in the configuration. + */ +int32_t AConfiguration_getSdkVersion(AConfiguration* config); + +/** + * Set the current SDK version in the configuration. + */ +void AConfiguration_setSdkVersion(AConfiguration* config, int32_t sdkVersion); + +/** + * Return the current ACONFIGURATION_SCREENSIZE_* set in the configuration. + */ +int32_t AConfiguration_getScreenSize(AConfiguration* config); + +/** + * Set the current screen size in the configuration. + */ +void AConfiguration_setScreenSize(AConfiguration* config, int32_t screenSize); + +/** + * Return the current ACONFIGURATION_SCREENLONG_* set in the configuration. + */ +int32_t AConfiguration_getScreenLong(AConfiguration* config); + +/** + * Set the current screen long in the configuration. + */ +void AConfiguration_setScreenLong(AConfiguration* config, int32_t screenLong); + +/** + * Return the current ACONFIGURATION_SCREENROUND_* set in the configuration. + */ +int32_t AConfiguration_getScreenRound(AConfiguration* config); + +/** + * Set the current screen round in the configuration. + */ +void AConfiguration_setScreenRound(AConfiguration* config, int32_t screenRound); + +/** + * Return the current ACONFIGURATION_UI_MODE_TYPE_* set in the configuration. + */ +int32_t AConfiguration_getUiModeType(AConfiguration* config); + +/** + * Set the current UI mode type in the configuration. + */ +void AConfiguration_setUiModeType(AConfiguration* config, int32_t uiModeType); + +/** + * Return the current ACONFIGURATION_UI_MODE_NIGHT_* set in the configuration. + */ +int32_t AConfiguration_getUiModeNight(AConfiguration* config); + +/** + * Set the current UI mode night in the configuration. + */ +void AConfiguration_setUiModeNight(AConfiguration* config, int32_t uiModeNight); + +/** + * Return the current configuration screen width in dp units, or + * ACONFIGURATION_SCREEN_WIDTH_DP_ANY if not set. + */ +int32_t AConfiguration_getScreenWidthDp(AConfiguration* config); + +/** + * Set the configuration's current screen width in dp units. + */ +void AConfiguration_setScreenWidthDp(AConfiguration* config, int32_t value); + +/** + * Return the current configuration screen height in dp units, or + * ACONFIGURATION_SCREEN_HEIGHT_DP_ANY if not set. + */ +int32_t AConfiguration_getScreenHeightDp(AConfiguration* config); + +/** + * Set the configuration's current screen width in dp units. + */ +void AConfiguration_setScreenHeightDp(AConfiguration* config, int32_t value); + +/** + * Return the configuration's smallest screen width in dp units, or + * ACONFIGURATION_SMALLEST_SCREEN_WIDTH_DP_ANY if not set. + */ +int32_t AConfiguration_getSmallestScreenWidthDp(AConfiguration* config); + +/** + * Set the configuration's smallest screen width in dp units. + */ +void AConfiguration_setSmallestScreenWidthDp(AConfiguration* config, int32_t value); + +/** + * Return the configuration's layout direction, or + * ACONFIGURATION_LAYOUTDIR_ANY if not set. + */ +int32_t AConfiguration_getLayoutDirection(AConfiguration* config); + +/** + * Set the configuration's layout direction. + */ +void AConfiguration_setLayoutDirection(AConfiguration* config, int32_t value); + +/** + * Perform a diff between two configurations. Returns a bit mask of + * ACONFIGURATION_* constants, each bit set meaning that configuration element + * is different between them. + */ +int32_t AConfiguration_diff(AConfiguration* config1, AConfiguration* config2); + +/** + * Determine whether 'base' is a valid configuration for use within the + * environment 'requested'. Returns 0 if there are any values in 'base' + * that conflict with 'requested'. Returns 1 if it does not conflict. + */ +int32_t AConfiguration_match(AConfiguration* base, AConfiguration* requested); + +/** + * Determine whether the configuration in 'test' is better than the existing + * configuration in 'base'. If 'requested' is non-NULL, this decision is based + * on the overall configuration given there. If it is NULL, this decision is + * simply based on which configuration is more specific. Returns non-0 if + * 'test' is better than 'base'. + * + * This assumes you have already filtered the configurations with + * AConfiguration_match(). + */ +int32_t AConfiguration_isBetterThan(AConfiguration* base, AConfiguration* test, + AConfiguration* requested); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_CONFIGURATION_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/input.h b/third_party/android_frameworks_native/include/android/input.h new file mode 100644 index 00000000000000..46cf89c7e1714b --- /dev/null +++ b/third_party/android_frameworks_native/include/android/input.h @@ -0,0 +1,1317 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Input + * @{ + */ + +/** + * @file input.h + */ + +#ifndef _ANDROID_INPUT_H +#define _ANDROID_INPUT_H + +/****************************************************************** + * + * IMPORTANT NOTICE: + * + * This file is part of Android's set of stable system headers + * exposed by the Android NDK (Native Development Kit). + * + * Third-party source AND binary code relies on the definitions + * here to be FROZEN ON ALL UPCOMING PLATFORM RELEASES. + * + * - DO NOT MODIFY ENUMS (EXCEPT IF YOU ADD NEW 32-BIT VALUES) + * - DO NOT MODIFY CONSTANTS OR FUNCTIONAL MACROS + * - DO NOT CHANGE THE SIGNATURE OF FUNCTIONS IN ANY WAY + * - DO NOT CHANGE THE LAYOUT OR SIZE OF STRUCTURES + */ + +/* + * Structures and functions to receive and process input events in + * native code. + * + * NOTE: These functions MUST be implemented by /system/lib/libui.so + */ + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Key states (may be returned by queries about the current state of a + * particular key code, scan code or switch). + */ +enum { + /** The key state is unknown or the requested key itself is not supported. */ + AKEY_STATE_UNKNOWN = -1, + + /** The key is up. */ + AKEY_STATE_UP = 0, + + /** The key is down. */ + AKEY_STATE_DOWN = 1, + + /** The key is down but is a virtual key press that is being emulated by the system. */ + AKEY_STATE_VIRTUAL = 2 +}; + +/** + * Meta key / modifer state. + */ +enum { + /** No meta keys are pressed. */ + AMETA_NONE = 0, + + /** This mask is used to check whether one of the ALT meta keys is pressed. */ + AMETA_ALT_ON = 0x02, + + /** This mask is used to check whether the left ALT meta key is pressed. */ + AMETA_ALT_LEFT_ON = 0x10, + + /** This mask is used to check whether the right ALT meta key is pressed. */ + AMETA_ALT_RIGHT_ON = 0x20, + + /** This mask is used to check whether one of the SHIFT meta keys is pressed. */ + AMETA_SHIFT_ON = 0x01, + + /** This mask is used to check whether the left SHIFT meta key is pressed. */ + AMETA_SHIFT_LEFT_ON = 0x40, + + /** This mask is used to check whether the right SHIFT meta key is pressed. */ + AMETA_SHIFT_RIGHT_ON = 0x80, + + /** This mask is used to check whether the SYM meta key is pressed. */ + AMETA_SYM_ON = 0x04, + + /** This mask is used to check whether the FUNCTION meta key is pressed. */ + AMETA_FUNCTION_ON = 0x08, + + /** This mask is used to check whether one of the CTRL meta keys is pressed. */ + AMETA_CTRL_ON = 0x1000, + + /** This mask is used to check whether the left CTRL meta key is pressed. */ + AMETA_CTRL_LEFT_ON = 0x2000, + + /** This mask is used to check whether the right CTRL meta key is pressed. */ + AMETA_CTRL_RIGHT_ON = 0x4000, + + /** This mask is used to check whether one of the META meta keys is pressed. */ + AMETA_META_ON = 0x10000, + + /** This mask is used to check whether the left META meta key is pressed. */ + AMETA_META_LEFT_ON = 0x20000, + + /** This mask is used to check whether the right META meta key is pressed. */ + AMETA_META_RIGHT_ON = 0x40000, + + /** This mask is used to check whether the CAPS LOCK meta key is on. */ + AMETA_CAPS_LOCK_ON = 0x100000, + + /** This mask is used to check whether the NUM LOCK meta key is on. */ + AMETA_NUM_LOCK_ON = 0x200000, + + /** This mask is used to check whether the SCROLL LOCK meta key is on. */ + AMETA_SCROLL_LOCK_ON = 0x400000, +}; + +struct AInputEvent; +/** + * Input events. + * + * Input events are opaque structures. Use the provided accessors functions to + * read their properties. + */ +typedef struct AInputEvent AInputEvent; + +/** + * Input event types. + */ +enum { + /** Indicates that the input event is a key event. */ + AINPUT_EVENT_TYPE_KEY = 1, + + /** Indicates that the input event is a motion event. */ + AINPUT_EVENT_TYPE_MOTION = 2 +}; + +/** + * Key event actions. + */ +enum { + /** The key has been pressed down. */ + AKEY_EVENT_ACTION_DOWN = 0, + + /** The key has been released. */ + AKEY_EVENT_ACTION_UP = 1, + + /** + * Multiple duplicate key events have occurred in a row, or a + * complex string is being delivered. The repeat_count property + * of the key event contains the number of times the given key + * code should be executed. + */ + AKEY_EVENT_ACTION_MULTIPLE = 2 +}; + +/** + * Key event flags. + */ +enum { + /** This mask is set if the device woke because of this key event. */ + AKEY_EVENT_FLAG_WOKE_HERE = 0x1, + + /** This mask is set if the key event was generated by a software keyboard. */ + AKEY_EVENT_FLAG_SOFT_KEYBOARD = 0x2, + + /** This mask is set if we don't want the key event to cause us to leave touch mode. */ + AKEY_EVENT_FLAG_KEEP_TOUCH_MODE = 0x4, + + /** + * This mask is set if an event was known to come from a trusted + * part of the system. That is, the event is known to come from + * the user, and could not have been spoofed by a third party + * component. + */ + AKEY_EVENT_FLAG_FROM_SYSTEM = 0x8, + + /** + * This mask is used for compatibility, to identify enter keys that are + * coming from an IME whose enter key has been auto-labelled "next" or + * "done". This allows TextView to dispatch these as normal enter keys + * for old applications, but still do the appropriate action when + * receiving them. + */ + AKEY_EVENT_FLAG_EDITOR_ACTION = 0x10, + + /** + * When associated with up key events, this indicates that the key press + * has been canceled. Typically this is used with virtual touch screen + * keys, where the user can slide from the virtual key area on to the + * display: in that case, the application will receive a canceled up + * event and should not perform the action normally associated with the + * key. Note that for this to work, the application can not perform an + * action for a key until it receives an up or the long press timeout has + * expired. + */ + AKEY_EVENT_FLAG_CANCELED = 0x20, + + /** + * This key event was generated by a virtual (on-screen) hard key area. + * Typically this is an area of the touchscreen, outside of the regular + * display, dedicated to "hardware" buttons. + */ + AKEY_EVENT_FLAG_VIRTUAL_HARD_KEY = 0x40, + + /** + * This flag is set for the first key repeat that occurs after the + * long press timeout. + */ + AKEY_EVENT_FLAG_LONG_PRESS = 0x80, + + /** + * Set when a key event has AKEY_EVENT_FLAG_CANCELED set because a long + * press action was executed while it was down. + */ + AKEY_EVENT_FLAG_CANCELED_LONG_PRESS = 0x100, + + /** + * Set for AKEY_EVENT_ACTION_UP when this event's key code is still being + * tracked from its initial down. That is, somebody requested that tracking + * started on the key down and a long press has not caused + * the tracking to be canceled. + */ + AKEY_EVENT_FLAG_TRACKING = 0x200, + + /** + * Set when a key event has been synthesized to implement default behavior + * for an event that the application did not handle. + * Fallback key events are generated by unhandled trackball motions + * (to emulate a directional keypad) and by certain unhandled key presses + * that are declared in the key map (such as special function numeric keypad + * keys when numlock is off). + */ + AKEY_EVENT_FLAG_FALLBACK = 0x400, +}; + +/** + * Bit shift for the action bits holding the pointer index as + * defined by AMOTION_EVENT_ACTION_POINTER_INDEX_MASK. + */ +#define AMOTION_EVENT_ACTION_POINTER_INDEX_SHIFT 8 + +/** Motion event actions */ +enum { + /** Bit mask of the parts of the action code that are the action itself. */ + AMOTION_EVENT_ACTION_MASK = 0xff, + + /** + * Bits in the action code that represent a pointer index, used with + * AMOTION_EVENT_ACTION_POINTER_DOWN and AMOTION_EVENT_ACTION_POINTER_UP. Shifting + * down by AMOTION_EVENT_ACTION_POINTER_INDEX_SHIFT provides the actual pointer + * index where the data for the pointer going up or down can be found. + */ + AMOTION_EVENT_ACTION_POINTER_INDEX_MASK = 0xff00, + + /** A pressed gesture has started, the motion contains the initial starting location. */ + AMOTION_EVENT_ACTION_DOWN = 0, + + /** + * A pressed gesture has finished, the motion contains the final release location + * as well as any intermediate points since the last down or move event. + */ + AMOTION_EVENT_ACTION_UP = 1, + + /** + * A change has happened during a press gesture (between AMOTION_EVENT_ACTION_DOWN and + * AMOTION_EVENT_ACTION_UP). The motion contains the most recent point, as well as + * any intermediate points since the last down or move event. + */ + AMOTION_EVENT_ACTION_MOVE = 2, + + /** + * The current gesture has been aborted. + * You will not receive any more points in it. You should treat this as + * an up event, but not perform any action that you normally would. + */ + AMOTION_EVENT_ACTION_CANCEL = 3, + + /** + * A movement has happened outside of the normal bounds of the UI element. + * This does not provide a full gesture, but only the initial location of the movement/touch. + */ + AMOTION_EVENT_ACTION_OUTSIDE = 4, + + /** + * A non-primary pointer has gone down. + * The bits in AMOTION_EVENT_ACTION_POINTER_INDEX_MASK indicate which pointer changed. + */ + AMOTION_EVENT_ACTION_POINTER_DOWN = 5, + + /** + * A non-primary pointer has gone up. + * The bits in AMOTION_EVENT_ACTION_POINTER_INDEX_MASK indicate which pointer changed. + */ + AMOTION_EVENT_ACTION_POINTER_UP = 6, + + /** + * A change happened but the pointer is not down (unlike AMOTION_EVENT_ACTION_MOVE). + * The motion contains the most recent point, as well as any intermediate points since + * the last hover move event. + */ + AMOTION_EVENT_ACTION_HOVER_MOVE = 7, + + /** + * The motion event contains relative vertical and/or horizontal scroll offsets. + * Use getAxisValue to retrieve the information from AMOTION_EVENT_AXIS_VSCROLL + * and AMOTION_EVENT_AXIS_HSCROLL. + * The pointer may or may not be down when this event is dispatched. + * This action is always delivered to the winder under the pointer, which + * may not be the window currently touched. + */ + AMOTION_EVENT_ACTION_SCROLL = 8, + + /** The pointer is not down but has entered the boundaries of a window or view. */ + AMOTION_EVENT_ACTION_HOVER_ENTER = 9, + + /** The pointer is not down but has exited the boundaries of a window or view. */ + AMOTION_EVENT_ACTION_HOVER_EXIT = 10, + + /* One or more buttons have been pressed. */ + AMOTION_EVENT_ACTION_BUTTON_PRESS = 11, + + /* One or more buttons have been released. */ + AMOTION_EVENT_ACTION_BUTTON_RELEASE = 12, +}; + +/** + * Motion event flags. + */ +enum { + /** + * This flag indicates that the window that received this motion event is partly + * or wholly obscured by another visible window above it. This flag is set to true + * even if the event did not directly pass through the obscured area. + * A security sensitive application can check this flag to identify situations in which + * a malicious application may have covered up part of its content for the purpose + * of misleading the user or hijacking touches. An appropriate response might be + * to drop the suspect touches or to take additional precautions to confirm the user's + * actual intent. + */ + AMOTION_EVENT_FLAG_WINDOW_IS_OBSCURED = 0x1, +}; + +/** + * Motion event edge touch flags. + */ +enum { + /** No edges intersected. */ + AMOTION_EVENT_EDGE_FLAG_NONE = 0, + + /** Flag indicating the motion event intersected the top edge of the screen. */ + AMOTION_EVENT_EDGE_FLAG_TOP = 0x01, + + /** Flag indicating the motion event intersected the bottom edge of the screen. */ + AMOTION_EVENT_EDGE_FLAG_BOTTOM = 0x02, + + /** Flag indicating the motion event intersected the left edge of the screen. */ + AMOTION_EVENT_EDGE_FLAG_LEFT = 0x04, + + /** Flag indicating the motion event intersected the right edge of the screen. */ + AMOTION_EVENT_EDGE_FLAG_RIGHT = 0x08 +}; + +/** + * Constants that identify each individual axis of a motion event. + * @anchor AMOTION_EVENT_AXIS + */ +enum { + /** + * Axis constant: X axis of a motion event. + * + * - For a touch screen, reports the absolute X screen position of the center of + * the touch contact area. The units are display pixels. + * - For a touch pad, reports the absolute X surface position of the center of the touch + * contact area. The units are device-dependent. + * - For a mouse, reports the absolute X screen position of the mouse pointer. + * The units are display pixels. + * - For a trackball, reports the relative horizontal displacement of the trackball. + * The value is normalized to a range from -1.0 (left) to 1.0 (right). + * - For a joystick, reports the absolute X position of the joystick. + * The value is normalized to a range from -1.0 (left) to 1.0 (right). + */ + AMOTION_EVENT_AXIS_X = 0, + /** + * Axis constant: Y axis of a motion event. + * + * - For a touch screen, reports the absolute Y screen position of the center of + * the touch contact area. The units are display pixels. + * - For a touch pad, reports the absolute Y surface position of the center of the touch + * contact area. The units are device-dependent. + * - For a mouse, reports the absolute Y screen position of the mouse pointer. + * The units are display pixels. + * - For a trackball, reports the relative vertical displacement of the trackball. + * The value is normalized to a range from -1.0 (up) to 1.0 (down). + * - For a joystick, reports the absolute Y position of the joystick. + * The value is normalized to a range from -1.0 (up or far) to 1.0 (down or near). + */ + AMOTION_EVENT_AXIS_Y = 1, + /** + * Axis constant: Pressure axis of a motion event. + * + * - For a touch screen or touch pad, reports the approximate pressure applied to the surface + * by a finger or other tool. The value is normalized to a range from + * 0 (no pressure at all) to 1 (normal pressure), although values higher than 1 + * may be generated depending on the calibration of the input device. + * - For a trackball, the value is set to 1 if the trackball button is pressed + * or 0 otherwise. + * - For a mouse, the value is set to 1 if the primary mouse button is pressed + * or 0 otherwise. + */ + AMOTION_EVENT_AXIS_PRESSURE = 2, + /** + * Axis constant: Size axis of a motion event. + * + * - For a touch screen or touch pad, reports the approximate size of the contact area in + * relation to the maximum detectable size for the device. The value is normalized + * to a range from 0 (smallest detectable size) to 1 (largest detectable size), + * although it is not a linear scale. This value is of limited use. + * To obtain calibrated size information, see + * {@link AMOTION_EVENT_AXIS_TOUCH_MAJOR} or {@link AMOTION_EVENT_AXIS_TOOL_MAJOR}. + */ + AMOTION_EVENT_AXIS_SIZE = 3, + /** + * Axis constant: TouchMajor axis of a motion event. + * + * - For a touch screen, reports the length of the major axis of an ellipse that + * represents the touch area at the point of contact. + * The units are display pixels. + * - For a touch pad, reports the length of the major axis of an ellipse that + * represents the touch area at the point of contact. + * The units are device-dependent. + */ + AMOTION_EVENT_AXIS_TOUCH_MAJOR = 4, + /** + * Axis constant: TouchMinor axis of a motion event. + * + * - For a touch screen, reports the length of the minor axis of an ellipse that + * represents the touch area at the point of contact. + * The units are display pixels. + * - For a touch pad, reports the length of the minor axis of an ellipse that + * represents the touch area at the point of contact. + * The units are device-dependent. + * + * When the touch is circular, the major and minor axis lengths will be equal to one another. + */ + AMOTION_EVENT_AXIS_TOUCH_MINOR = 5, + /** + * Axis constant: ToolMajor axis of a motion event. + * + * - For a touch screen, reports the length of the major axis of an ellipse that + * represents the size of the approaching finger or tool used to make contact. + * - For a touch pad, reports the length of the major axis of an ellipse that + * represents the size of the approaching finger or tool used to make contact. + * The units are device-dependent. + * + * When the touch is circular, the major and minor axis lengths will be equal to one another. + * + * The tool size may be larger than the touch size since the tool may not be fully + * in contact with the touch sensor. + */ + AMOTION_EVENT_AXIS_TOOL_MAJOR = 6, + /** + * Axis constant: ToolMinor axis of a motion event. + * + * - For a touch screen, reports the length of the minor axis of an ellipse that + * represents the size of the approaching finger or tool used to make contact. + * - For a touch pad, reports the length of the minor axis of an ellipse that + * represents the size of the approaching finger or tool used to make contact. + * The units are device-dependent. + * + * When the touch is circular, the major and minor axis lengths will be equal to one another. + * + * The tool size may be larger than the touch size since the tool may not be fully + * in contact with the touch sensor. + */ + AMOTION_EVENT_AXIS_TOOL_MINOR = 7, + /** + * Axis constant: Orientation axis of a motion event. + * + * - For a touch screen or touch pad, reports the orientation of the finger + * or tool in radians relative to the vertical plane of the device. + * An angle of 0 radians indicates that the major axis of contact is oriented + * upwards, is perfectly circular or is of unknown orientation. A positive angle + * indicates that the major axis of contact is oriented to the right. A negative angle + * indicates that the major axis of contact is oriented to the left. + * The full range is from -PI/2 radians (finger pointing fully left) to PI/2 radians + * (finger pointing fully right). + * - For a stylus, the orientation indicates the direction in which the stylus + * is pointing in relation to the vertical axis of the current orientation of the screen. + * The range is from -PI radians to PI radians, where 0 is pointing up, + * -PI/2 radians is pointing left, -PI or PI radians is pointing down, and PI/2 radians + * is pointing right. See also {@link AMOTION_EVENT_AXIS_TILT}. + */ + AMOTION_EVENT_AXIS_ORIENTATION = 8, + /** + * Axis constant: Vertical Scroll axis of a motion event. + * + * - For a mouse, reports the relative movement of the vertical scroll wheel. + * The value is normalized to a range from -1.0 (down) to 1.0 (up). + * + * This axis should be used to scroll views vertically. + */ + AMOTION_EVENT_AXIS_VSCROLL = 9, + /** + * Axis constant: Horizontal Scroll axis of a motion event. + * + * - For a mouse, reports the relative movement of the horizontal scroll wheel. + * The value is normalized to a range from -1.0 (left) to 1.0 (right). + * + * This axis should be used to scroll views horizontally. + */ + AMOTION_EVENT_AXIS_HSCROLL = 10, + /** + * Axis constant: Z axis of a motion event. + * + * - For a joystick, reports the absolute Z position of the joystick. + * The value is normalized to a range from -1.0 (high) to 1.0 (low). + * On game pads with two analog joysticks, this axis is often reinterpreted + * to report the absolute X position of the second joystick instead. + */ + AMOTION_EVENT_AXIS_Z = 11, + /** + * Axis constant: X Rotation axis of a motion event. + * + * - For a joystick, reports the absolute rotation angle about the X axis. + * The value is normalized to a range from -1.0 (counter-clockwise) to 1.0 (clockwise). + */ + AMOTION_EVENT_AXIS_RX = 12, + /** + * Axis constant: Y Rotation axis of a motion event. + * + * - For a joystick, reports the absolute rotation angle about the Y axis. + * The value is normalized to a range from -1.0 (counter-clockwise) to 1.0 (clockwise). + */ + AMOTION_EVENT_AXIS_RY = 13, + /** + * Axis constant: Z Rotation axis of a motion event. + * + * - For a joystick, reports the absolute rotation angle about the Z axis. + * The value is normalized to a range from -1.0 (counter-clockwise) to 1.0 (clockwise). + * On game pads with two analog joysticks, this axis is often reinterpreted + * to report the absolute Y position of the second joystick instead. + */ + AMOTION_EVENT_AXIS_RZ = 14, + /** + * Axis constant: Hat X axis of a motion event. + * + * - For a joystick, reports the absolute X position of the directional hat control. + * The value is normalized to a range from -1.0 (left) to 1.0 (right). + */ + AMOTION_EVENT_AXIS_HAT_X = 15, + /** + * Axis constant: Hat Y axis of a motion event. + * + * - For a joystick, reports the absolute Y position of the directional hat control. + * The value is normalized to a range from -1.0 (up) to 1.0 (down). + */ + AMOTION_EVENT_AXIS_HAT_Y = 16, + /** + * Axis constant: Left Trigger axis of a motion event. + * + * - For a joystick, reports the absolute position of the left trigger control. + * The value is normalized to a range from 0.0 (released) to 1.0 (fully pressed). + */ + AMOTION_EVENT_AXIS_LTRIGGER = 17, + /** + * Axis constant: Right Trigger axis of a motion event. + * + * - For a joystick, reports the absolute position of the right trigger control. + * The value is normalized to a range from 0.0 (released) to 1.0 (fully pressed). + */ + AMOTION_EVENT_AXIS_RTRIGGER = 18, + /** + * Axis constant: Throttle axis of a motion event. + * + * - For a joystick, reports the absolute position of the throttle control. + * The value is normalized to a range from 0.0 (fully open) to 1.0 (fully closed). + */ + AMOTION_EVENT_AXIS_THROTTLE = 19, + /** + * Axis constant: Rudder axis of a motion event. + * + * - For a joystick, reports the absolute position of the rudder control. + * The value is normalized to a range from -1.0 (turn left) to 1.0 (turn right). + */ + AMOTION_EVENT_AXIS_RUDDER = 20, + /** + * Axis constant: Wheel axis of a motion event. + * + * - For a joystick, reports the absolute position of the steering wheel control. + * The value is normalized to a range from -1.0 (turn left) to 1.0 (turn right). + */ + AMOTION_EVENT_AXIS_WHEEL = 21, + /** + * Axis constant: Gas axis of a motion event. + * + * - For a joystick, reports the absolute position of the gas (accelerator) control. + * The value is normalized to a range from 0.0 (no acceleration) + * to 1.0 (maximum acceleration). + */ + AMOTION_EVENT_AXIS_GAS = 22, + /** + * Axis constant: Brake axis of a motion event. + * + * - For a joystick, reports the absolute position of the brake control. + * The value is normalized to a range from 0.0 (no braking) to 1.0 (maximum braking). + */ + AMOTION_EVENT_AXIS_BRAKE = 23, + /** + * Axis constant: Distance axis of a motion event. + * + * - For a stylus, reports the distance of the stylus from the screen. + * A value of 0.0 indicates direct contact and larger values indicate increasing + * distance from the surface. + */ + AMOTION_EVENT_AXIS_DISTANCE = 24, + /** + * Axis constant: Tilt axis of a motion event. + * + * - For a stylus, reports the tilt angle of the stylus in radians where + * 0 radians indicates that the stylus is being held perpendicular to the + * surface, and PI/2 radians indicates that the stylus is being held flat + * against the surface. + */ + AMOTION_EVENT_AXIS_TILT = 25, + /** + * Axis constant: Generic 1 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_1 = 32, + /** + * Axis constant: Generic 2 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_2 = 33, + /** + * Axis constant: Generic 3 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_3 = 34, + /** + * Axis constant: Generic 4 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_4 = 35, + /** + * Axis constant: Generic 5 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_5 = 36, + /** + * Axis constant: Generic 6 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_6 = 37, + /** + * Axis constant: Generic 7 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_7 = 38, + /** + * Axis constant: Generic 8 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_8 = 39, + /** + * Axis constant: Generic 9 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_9 = 40, + /** + * Axis constant: Generic 10 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_10 = 41, + /** + * Axis constant: Generic 11 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_11 = 42, + /** + * Axis constant: Generic 12 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_12 = 43, + /** + * Axis constant: Generic 13 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_13 = 44, + /** + * Axis constant: Generic 14 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_14 = 45, + /** + * Axis constant: Generic 15 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_15 = 46, + /** + * Axis constant: Generic 16 axis of a motion event. + * The interpretation of a generic axis is device-specific. + */ + AMOTION_EVENT_AXIS_GENERIC_16 = 47, + + // NOTE: If you add a new axis here you must also add it to several other files. + // Refer to frameworks/base/core/java/android/view/MotionEvent.java for the full list. +}; + +/** + * Constants that identify buttons that are associated with motion events. + * Refer to the documentation on the MotionEvent class for descriptions of each button. + */ +enum { + /** primary */ + AMOTION_EVENT_BUTTON_PRIMARY = 1 << 0, + /** secondary */ + AMOTION_EVENT_BUTTON_SECONDARY = 1 << 1, + /** tertiary */ + AMOTION_EVENT_BUTTON_TERTIARY = 1 << 2, + /** back */ + AMOTION_EVENT_BUTTON_BACK = 1 << 3, + /** forward */ + AMOTION_EVENT_BUTTON_FORWARD = 1 << 4, + AMOTION_EVENT_BUTTON_STYLUS_PRIMARY = 1 << 5, + AMOTION_EVENT_BUTTON_STYLUS_SECONDARY = 1 << 6, +}; + +/** + * Constants that identify tool types. + * Refer to the documentation on the MotionEvent class for descriptions of each tool type. + */ +enum { + /** unknown */ + AMOTION_EVENT_TOOL_TYPE_UNKNOWN = 0, + /** finger */ + AMOTION_EVENT_TOOL_TYPE_FINGER = 1, + /** stylus */ + AMOTION_EVENT_TOOL_TYPE_STYLUS = 2, + /** mouse */ + AMOTION_EVENT_TOOL_TYPE_MOUSE = 3, + /** eraser */ + AMOTION_EVENT_TOOL_TYPE_ERASER = 4, +}; + +/** + * Input source masks. + * + * Refer to the documentation on android.view.InputDevice for more details about input sources + * and their correct interpretation. + */ +enum { + /** mask */ + AINPUT_SOURCE_CLASS_MASK = 0x000000ff, + + /** none */ + AINPUT_SOURCE_CLASS_NONE = 0x00000000, + /** button */ + AINPUT_SOURCE_CLASS_BUTTON = 0x00000001, + /** pointer */ + AINPUT_SOURCE_CLASS_POINTER = 0x00000002, + /** navigation */ + AINPUT_SOURCE_CLASS_NAVIGATION = 0x00000004, + /** position */ + AINPUT_SOURCE_CLASS_POSITION = 0x00000008, + /** joystick */ + AINPUT_SOURCE_CLASS_JOYSTICK = 0x00000010, +}; + +/** + * Input sources. + */ +enum { + /** unknown */ + AINPUT_SOURCE_UNKNOWN = 0x00000000, + + /** keyboard */ + AINPUT_SOURCE_KEYBOARD = 0x00000100 | AINPUT_SOURCE_CLASS_BUTTON, + /** dpad */ + AINPUT_SOURCE_DPAD = 0x00000200 | AINPUT_SOURCE_CLASS_BUTTON, + /** gamepad */ + AINPUT_SOURCE_GAMEPAD = 0x00000400 | AINPUT_SOURCE_CLASS_BUTTON, + /** touchscreen */ + AINPUT_SOURCE_TOUCHSCREEN = 0x00001000 | AINPUT_SOURCE_CLASS_POINTER, + /** mouse */ + AINPUT_SOURCE_MOUSE = 0x00002000 | AINPUT_SOURCE_CLASS_POINTER, + /** stylus */ + AINPUT_SOURCE_STYLUS = 0x00004000 | AINPUT_SOURCE_CLASS_POINTER, + /** bluetooth stylus */ + AINPUT_SOURCE_BLUETOOTH_STYLUS = 0x00008000 | AINPUT_SOURCE_STYLUS, + /** trackball */ + AINPUT_SOURCE_TRACKBALL = 0x00010000 | AINPUT_SOURCE_CLASS_NAVIGATION, + /** touchpad */ + AINPUT_SOURCE_TOUCHPAD = 0x00100000 | AINPUT_SOURCE_CLASS_POSITION, + /** navigation */ + AINPUT_SOURCE_TOUCH_NAVIGATION = 0x00200000 | AINPUT_SOURCE_CLASS_NONE, + /** gesture sensor (?) */ + AINPUT_SOURCE_GESTURE_SENSOR = 0x00400000 | AINPUT_SOURCE_CLASS_NONE, + /** joystick */ + AINPUT_SOURCE_JOYSTICK = 0x01000000 | AINPUT_SOURCE_CLASS_JOYSTICK, + + /** any */ + AINPUT_SOURCE_ANY = 0xffffff00, +}; + +/** + * Keyboard types. + * + * Refer to the documentation on android.view.InputDevice for more details. + */ +enum { + /** none */ + AINPUT_KEYBOARD_TYPE_NONE = 0, + /** non alphabetic */ + AINPUT_KEYBOARD_TYPE_NON_ALPHABETIC = 1, + /** alphabetic */ + AINPUT_KEYBOARD_TYPE_ALPHABETIC = 2, +}; + +/** + * Constants used to retrieve information about the range of motion for a particular + * coordinate of a motion event. + * + * Refer to the documentation on android.view.InputDevice for more details about input sources + * and their correct interpretation. + * + * @deprecated These constants are deprecated. Use {@link AMOTION_EVENT_AXIS AMOTION_EVENT_AXIS_*} constants instead. + */ +enum { + /** x */ + AINPUT_MOTION_RANGE_X = AMOTION_EVENT_AXIS_X, + /** y */ + AINPUT_MOTION_RANGE_Y = AMOTION_EVENT_AXIS_Y, + /** pressure */ + AINPUT_MOTION_RANGE_PRESSURE = AMOTION_EVENT_AXIS_PRESSURE, + /** size */ + AINPUT_MOTION_RANGE_SIZE = AMOTION_EVENT_AXIS_SIZE, + /** touch major */ + AINPUT_MOTION_RANGE_TOUCH_MAJOR = AMOTION_EVENT_AXIS_TOUCH_MAJOR, + /** touch minor */ + AINPUT_MOTION_RANGE_TOUCH_MINOR = AMOTION_EVENT_AXIS_TOUCH_MINOR, + /** tool major */ + AINPUT_MOTION_RANGE_TOOL_MAJOR = AMOTION_EVENT_AXIS_TOOL_MAJOR, + /** tool minor */ + AINPUT_MOTION_RANGE_TOOL_MINOR = AMOTION_EVENT_AXIS_TOOL_MINOR, + /** orientation */ + AINPUT_MOTION_RANGE_ORIENTATION = AMOTION_EVENT_AXIS_ORIENTATION, +}; + + +/** + * Input event accessors. + * + * Note that most functions can only be used on input events that are of a given type. + * Calling these functions on input events of other types will yield undefined behavior. + */ + +/*** Accessors for all input events. ***/ + +/** Get the input event type. */ +int32_t AInputEvent_getType(const AInputEvent* event); + +/** Get the id for the device that an input event came from. + * + * Input events can be generated by multiple different input devices. + * Use the input device id to obtain information about the input + * device that was responsible for generating a particular event. + * + * An input device id of 0 indicates that the event didn't come from a physical device; + * other numbers are arbitrary and you shouldn't depend on the values. + * Use the provided input device query API to obtain information about input devices. + */ +int32_t AInputEvent_getDeviceId(const AInputEvent* event); + +/** Get the input event source. */ +int32_t AInputEvent_getSource(const AInputEvent* event); + +/*** Accessors for key events only. ***/ + +/** Get the key event action. */ +int32_t AKeyEvent_getAction(const AInputEvent* key_event); + +/** Get the key event flags. */ +int32_t AKeyEvent_getFlags(const AInputEvent* key_event); + +/** + * Get the key code of the key event. + * This is the physical key that was pressed, not the Unicode character. + */ +int32_t AKeyEvent_getKeyCode(const AInputEvent* key_event); + +/** + * Get the hardware key id of this key event. + * These values are not reliable and vary from device to device. + */ +int32_t AKeyEvent_getScanCode(const AInputEvent* key_event); + +/** Get the meta key state. */ +int32_t AKeyEvent_getMetaState(const AInputEvent* key_event); + +/** + * Get the repeat count of the event. + * For both key up an key down events, this is the number of times the key has + * repeated with the first down starting at 0 and counting up from there. For + * multiple key events, this is the number of down/up pairs that have occurred. + */ +int32_t AKeyEvent_getRepeatCount(const AInputEvent* key_event); + +/** + * Get the time of the most recent key down event, in the + * java.lang.System.nanoTime() time base. If this is a down event, + * this will be the same as eventTime. + * Note that when chording keys, this value is the down time of the most recently + * pressed key, which may not be the same physical key of this event. + */ +int64_t AKeyEvent_getDownTime(const AInputEvent* key_event); + +/** + * Get the time this event occurred, in the + * java.lang.System.nanoTime() time base. + */ +int64_t AKeyEvent_getEventTime(const AInputEvent* key_event); + +/*** Accessors for motion events only. ***/ + +/** Get the combined motion event action code and pointer index. */ +int32_t AMotionEvent_getAction(const AInputEvent* motion_event); + +/** Get the motion event flags. */ +int32_t AMotionEvent_getFlags(const AInputEvent* motion_event); + +/** + * Get the state of any meta / modifier keys that were in effect when the + * event was generated. + */ +int32_t AMotionEvent_getMetaState(const AInputEvent* motion_event); + +/** Get the button state of all buttons that are pressed. */ +int32_t AMotionEvent_getButtonState(const AInputEvent* motion_event); + +/** + * Get a bitfield indicating which edges, if any, were touched by this motion event. + * For touch events, clients can use this to determine if the user's finger was + * touching the edge of the display. + */ +int32_t AMotionEvent_getEdgeFlags(const AInputEvent* motion_event); + +/** + * Get the time when the user originally pressed down to start a stream of + * position events, in the java.lang.System.nanoTime() time base. + */ +int64_t AMotionEvent_getDownTime(const AInputEvent* motion_event); + +/** + * Get the time when this specific event was generated, + * in the java.lang.System.nanoTime() time base. + */ +int64_t AMotionEvent_getEventTime(const AInputEvent* motion_event); + +/** + * Get the X coordinate offset. + * For touch events on the screen, this is the delta that was added to the raw + * screen coordinates to adjust for the absolute position of the containing windows + * and views. + */ +float AMotionEvent_getXOffset(const AInputEvent* motion_event); + +/** + * Get the Y coordinate offset. + * For touch events on the screen, this is the delta that was added to the raw + * screen coordinates to adjust for the absolute position of the containing windows + * and views. + */ +float AMotionEvent_getYOffset(const AInputEvent* motion_event); + +/** + * Get the precision of the X coordinates being reported. + * You can multiply this number with an X coordinate sample to find the + * actual hardware value of the X coordinate. + */ +float AMotionEvent_getXPrecision(const AInputEvent* motion_event); + +/** + * Get the precision of the Y coordinates being reported. + * You can multiply this number with a Y coordinate sample to find the + * actual hardware value of the Y coordinate. + */ +float AMotionEvent_getYPrecision(const AInputEvent* motion_event); + +/** + * Get the number of pointers of data contained in this event. + * Always >= 1. + */ +size_t AMotionEvent_getPointerCount(const AInputEvent* motion_event); + +/** + * Get the pointer identifier associated with a particular pointer + * data index in this event. The identifier tells you the actual pointer + * number associated with the data, accounting for individual pointers + * going up and down since the start of the current gesture. + */ +int32_t AMotionEvent_getPointerId(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the tool type of a pointer for the given pointer index. + * The tool type indicates the type of tool used to make contact such as a + * finger or stylus, if known. + */ +int32_t AMotionEvent_getToolType(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the original raw X coordinate of this event. + * For touch events on the screen, this is the original location of the event + * on the screen, before it had been adjusted for the containing window + * and views. + */ +float AMotionEvent_getRawX(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the original raw X coordinate of this event. + * For touch events on the screen, this is the original location of the event + * on the screen, before it had been adjusted for the containing window + * and views. + */ +float AMotionEvent_getRawY(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current X coordinate of this event for the given pointer index. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getX(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current Y coordinate of this event for the given pointer index. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getY(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current pressure of this event for the given pointer index. + * The pressure generally ranges from 0 (no pressure at all) to 1 (normal pressure), + * although values higher than 1 may be generated depending on the calibration of + * the input device. + */ +float AMotionEvent_getPressure(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current scaled value of the approximate size for the given pointer index. + * This represents some approximation of the area of the screen being + * pressed; the actual value in pixels corresponding to the + * touch is normalized with the device specific range of values + * and scaled to a value between 0 and 1. The value of size can be used to + * determine fat touch events. + */ +float AMotionEvent_getSize(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current length of the major axis of an ellipse that describes the touch area + * at the point of contact for the given pointer index. + */ +float AMotionEvent_getTouchMajor(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current length of the minor axis of an ellipse that describes the touch area + * at the point of contact for the given pointer index. + */ +float AMotionEvent_getTouchMinor(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current length of the major axis of an ellipse that describes the size + * of the approaching tool for the given pointer index. + * The tool area represents the estimated size of the finger or pen that is + * touching the device independent of its actual touch area at the point of contact. + */ +float AMotionEvent_getToolMajor(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current length of the minor axis of an ellipse that describes the size + * of the approaching tool for the given pointer index. + * The tool area represents the estimated size of the finger or pen that is + * touching the device independent of its actual touch area at the point of contact. + */ +float AMotionEvent_getToolMinor(const AInputEvent* motion_event, size_t pointer_index); + +/** + * Get the current orientation of the touch area and tool area in radians clockwise from + * vertical for the given pointer index. + * An angle of 0 degrees indicates that the major axis of contact is oriented + * upwards, is perfectly circular or is of unknown orientation. A positive angle + * indicates that the major axis of contact is oriented to the right. A negative angle + * indicates that the major axis of contact is oriented to the left. + * The full range is from -PI/2 radians (finger pointing fully left) to PI/2 radians + * (finger pointing fully right). + */ +float AMotionEvent_getOrientation(const AInputEvent* motion_event, size_t pointer_index); + +/** Get the value of the request axis for the given pointer index. */ +float AMotionEvent_getAxisValue(const AInputEvent* motion_event, + int32_t axis, size_t pointer_index); + +/** + * Get the number of historical points in this event. These are movements that + * have occurred between this event and the previous event. This only applies + * to AMOTION_EVENT_ACTION_MOVE events -- all other actions will have a size of 0. + * Historical samples are indexed from oldest to newest. + */ +size_t AMotionEvent_getHistorySize(const AInputEvent* motion_event); + +/** + * Get the time that a historical movement occurred between this event and + * the previous event, in the java.lang.System.nanoTime() time base. + */ +int64_t AMotionEvent_getHistoricalEventTime(const AInputEvent* motion_event, + size_t history_index); + +/** + * Get the historical raw X coordinate of this event for the given pointer index that + * occurred between this event and the previous motion event. + * For touch events on the screen, this is the original location of the event + * on the screen, before it had been adjusted for the containing window + * and views. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getHistoricalRawX(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical raw Y coordinate of this event for the given pointer index that + * occurred between this event and the previous motion event. + * For touch events on the screen, this is the original location of the event + * on the screen, before it had been adjusted for the containing window + * and views. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getHistoricalRawY(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical X coordinate of this event for the given pointer index that + * occurred between this event and the previous motion event. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getHistoricalX(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical Y coordinate of this event for the given pointer index that + * occurred between this event and the previous motion event. + * Whole numbers are pixels; the value may have a fraction for input devices + * that are sub-pixel precise. + */ +float AMotionEvent_getHistoricalY(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical pressure of this event for the given pointer index that + * occurred between this event and the previous motion event. + * The pressure generally ranges from 0 (no pressure at all) to 1 (normal pressure), + * although values higher than 1 may be generated depending on the calibration of + * the input device. + */ +float AMotionEvent_getHistoricalPressure(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the current scaled value of the approximate size for the given pointer index that + * occurred between this event and the previous motion event. + * This represents some approximation of the area of the screen being + * pressed; the actual value in pixels corresponding to the + * touch is normalized with the device specific range of values + * and scaled to a value between 0 and 1. The value of size can be used to + * determine fat touch events. + */ +float AMotionEvent_getHistoricalSize(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical length of the major axis of an ellipse that describes the touch area + * at the point of contact for the given pointer index that + * occurred between this event and the previous motion event. + */ +float AMotionEvent_getHistoricalTouchMajor(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical length of the minor axis of an ellipse that describes the touch area + * at the point of contact for the given pointer index that + * occurred between this event and the previous motion event. + */ +float AMotionEvent_getHistoricalTouchMinor(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical length of the major axis of an ellipse that describes the size + * of the approaching tool for the given pointer index that + * occurred between this event and the previous motion event. + * The tool area represents the estimated size of the finger or pen that is + * touching the device independent of its actual touch area at the point of contact. + */ +float AMotionEvent_getHistoricalToolMajor(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical length of the minor axis of an ellipse that describes the size + * of the approaching tool for the given pointer index that + * occurred between this event and the previous motion event. + * The tool area represents the estimated size of the finger or pen that is + * touching the device independent of its actual touch area at the point of contact. + */ +float AMotionEvent_getHistoricalToolMinor(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical orientation of the touch area and tool area in radians clockwise from + * vertical for the given pointer index that + * occurred between this event and the previous motion event. + * An angle of 0 degrees indicates that the major axis of contact is oriented + * upwards, is perfectly circular or is of unknown orientation. A positive angle + * indicates that the major axis of contact is oriented to the right. A negative angle + * indicates that the major axis of contact is oriented to the left. + * The full range is from -PI/2 radians (finger pointing fully left) to PI/2 radians + * (finger pointing fully right). + */ +float AMotionEvent_getHistoricalOrientation(const AInputEvent* motion_event, size_t pointer_index, + size_t history_index); + +/** + * Get the historical value of the request axis for the given pointer index + * that occurred between this event and the previous motion event. + */ +float AMotionEvent_getHistoricalAxisValue(const AInputEvent* motion_event, + int32_t axis, size_t pointer_index, size_t history_index); + + +struct AInputQueue; +/** + * Input queue + * + * An input queue is the facility through which you retrieve input + * events. + */ +typedef struct AInputQueue AInputQueue; + +/** + * Add this input queue to a looper for processing. See + * ALooper_addFd() for information on the ident, callback, and data params. + */ +void AInputQueue_attachLooper(AInputQueue* queue, ALooper* looper, + int ident, ALooper_callbackFunc callback, void* data); + +/** + * Remove the input queue from the looper it is currently attached to. + */ +void AInputQueue_detachLooper(AInputQueue* queue); + +/** + * Returns true if there are one or more events available in the + * input queue. Returns 1 if the queue has events; 0 if + * it does not have events; and a negative value if there is an error. + */ +int32_t AInputQueue_hasEvents(AInputQueue* queue); + +/** + * Returns the next available event from the queue. Returns a negative + * value if no events are available or an error has occurred. + */ +int32_t AInputQueue_getEvent(AInputQueue* queue, AInputEvent** outEvent); + +/** + * Sends the key for standard pre-dispatching -- that is, possibly deliver + * it to the current IME to be consumed before the app. Returns 0 if it + * was not pre-dispatched, meaning you can process it right now. If non-zero + * is returned, you must abandon the current event processing and allow the + * event to appear again in the event queue (if it does not get consumed during + * pre-dispatching). + */ +int32_t AInputQueue_preDispatchEvent(AInputQueue* queue, AInputEvent* event); + +/** + * Report that dispatching has finished with the given event. + * This must be called after receiving an event with AInputQueue_get_event(). + */ +void AInputQueue_finishEvent(AInputQueue* queue, AInputEvent* event, int handled); + +#ifdef __cplusplus +} +#endif + +#endif // _ANDROID_INPUT_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/keycodes.h b/third_party/android_frameworks_native/include/android/keycodes.h new file mode 100644 index 00000000000000..421abe54777d9d --- /dev/null +++ b/third_party/android_frameworks_native/include/android/keycodes.h @@ -0,0 +1,752 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Input + * @{ + */ + +/** + * @file keycodes.h + */ + +#ifndef _ANDROID_KEYCODES_H +#define _ANDROID_KEYCODES_H + +/****************************************************************** + * + * IMPORTANT NOTICE: + * + * This file is part of Android's set of stable system headers + * exposed by the Android NDK (Native Development Kit). + * + * Third-party source AND binary code relies on the definitions + * here to be FROZEN ON ALL UPCOMING PLATFORM RELEASES. + * + * - DO NOT MODIFY ENUMS (EXCEPT IF YOU ADD NEW 32-BIT VALUES) + * - DO NOT MODIFY CONSTANTS OR FUNCTIONAL MACROS + * - DO NOT CHANGE THE SIGNATURE OF FUNCTIONS IN ANY WAY + * - DO NOT CHANGE THE LAYOUT OR SIZE OF STRUCTURES + */ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Key codes. + */ +enum { + /** Unknown key code. */ + AKEYCODE_UNKNOWN = 0, + /** Soft Left key. + * Usually situated below the display on phones and used as a multi-function + * feature key for selecting a software defined function shown on the bottom left + * of the display. */ + AKEYCODE_SOFT_LEFT = 1, + /** Soft Right key. + * Usually situated below the display on phones and used as a multi-function + * feature key for selecting a software defined function shown on the bottom right + * of the display. */ + AKEYCODE_SOFT_RIGHT = 2, + /** Home key. + * This key is handled by the framework and is never delivered to applications. */ + AKEYCODE_HOME = 3, + /** Back key. */ + AKEYCODE_BACK = 4, + /** Call key. */ + AKEYCODE_CALL = 5, + /** End Call key. */ + AKEYCODE_ENDCALL = 6, + /** '0' key. */ + AKEYCODE_0 = 7, + /** '1' key. */ + AKEYCODE_1 = 8, + /** '2' key. */ + AKEYCODE_2 = 9, + /** '3' key. */ + AKEYCODE_3 = 10, + /** '4' key. */ + AKEYCODE_4 = 11, + /** '5' key. */ + AKEYCODE_5 = 12, + /** '6' key. */ + AKEYCODE_6 = 13, + /** '7' key. */ + AKEYCODE_7 = 14, + /** '8' key. */ + AKEYCODE_8 = 15, + /** '9' key. */ + AKEYCODE_9 = 16, + /** '*' key. */ + AKEYCODE_STAR = 17, + /** '#' key. */ + AKEYCODE_POUND = 18, + /** Directional Pad Up key. + * May also be synthesized from trackball motions. */ + AKEYCODE_DPAD_UP = 19, + /** Directional Pad Down key. + * May also be synthesized from trackball motions. */ + AKEYCODE_DPAD_DOWN = 20, + /** Directional Pad Left key. + * May also be synthesized from trackball motions. */ + AKEYCODE_DPAD_LEFT = 21, + /** Directional Pad Right key. + * May also be synthesized from trackball motions. */ + AKEYCODE_DPAD_RIGHT = 22, + /** Directional Pad Center key. + * May also be synthesized from trackball motions. */ + AKEYCODE_DPAD_CENTER = 23, + /** Volume Up key. + * Adjusts the speaker volume up. */ + AKEYCODE_VOLUME_UP = 24, + /** Volume Down key. + * Adjusts the speaker volume down. */ + AKEYCODE_VOLUME_DOWN = 25, + /** Power key. */ + AKEYCODE_POWER = 26, + /** Camera key. + * Used to launch a camera application or take pictures. */ + AKEYCODE_CAMERA = 27, + /** Clear key. */ + AKEYCODE_CLEAR = 28, + /** 'A' key. */ + AKEYCODE_A = 29, + /** 'B' key. */ + AKEYCODE_B = 30, + /** 'C' key. */ + AKEYCODE_C = 31, + /** 'D' key. */ + AKEYCODE_D = 32, + /** 'E' key. */ + AKEYCODE_E = 33, + /** 'F' key. */ + AKEYCODE_F = 34, + /** 'G' key. */ + AKEYCODE_G = 35, + /** 'H' key. */ + AKEYCODE_H = 36, + /** 'I' key. */ + AKEYCODE_I = 37, + /** 'J' key. */ + AKEYCODE_J = 38, + /** 'K' key. */ + AKEYCODE_K = 39, + /** 'L' key. */ + AKEYCODE_L = 40, + /** 'M' key. */ + AKEYCODE_M = 41, + /** 'N' key. */ + AKEYCODE_N = 42, + /** 'O' key. */ + AKEYCODE_O = 43, + /** 'P' key. */ + AKEYCODE_P = 44, + /** 'Q' key. */ + AKEYCODE_Q = 45, + /** 'R' key. */ + AKEYCODE_R = 46, + /** 'S' key. */ + AKEYCODE_S = 47, + /** 'T' key. */ + AKEYCODE_T = 48, + /** 'U' key. */ + AKEYCODE_U = 49, + /** 'V' key. */ + AKEYCODE_V = 50, + /** 'W' key. */ + AKEYCODE_W = 51, + /** 'X' key. */ + AKEYCODE_X = 52, + /** 'Y' key. */ + AKEYCODE_Y = 53, + /** 'Z' key. */ + AKEYCODE_Z = 54, + /** ',' key. */ + AKEYCODE_COMMA = 55, + /** '.' key. */ + AKEYCODE_PERIOD = 56, + /** Left Alt modifier key. */ + AKEYCODE_ALT_LEFT = 57, + /** Right Alt modifier key. */ + AKEYCODE_ALT_RIGHT = 58, + /** Left Shift modifier key. */ + AKEYCODE_SHIFT_LEFT = 59, + /** Right Shift modifier key. */ + AKEYCODE_SHIFT_RIGHT = 60, + /** Tab key. */ + AKEYCODE_TAB = 61, + /** Space key. */ + AKEYCODE_SPACE = 62, + /** Symbol modifier key. + * Used to enter alternate symbols. */ + AKEYCODE_SYM = 63, + /** Explorer special function key. + * Used to launch a browser application. */ + AKEYCODE_EXPLORER = 64, + /** Envelope special function key. + * Used to launch a mail application. */ + AKEYCODE_ENVELOPE = 65, + /** Enter key. */ + AKEYCODE_ENTER = 66, + /** Backspace key. + * Deletes characters before the insertion point, unlike {@link AKEYCODE_FORWARD_DEL}. */ + AKEYCODE_DEL = 67, + /** '`' (backtick) key. */ + AKEYCODE_GRAVE = 68, + /** '-'. */ + AKEYCODE_MINUS = 69, + /** '=' key. */ + AKEYCODE_EQUALS = 70, + /** '[' key. */ + AKEYCODE_LEFT_BRACKET = 71, + /** ']' key. */ + AKEYCODE_RIGHT_BRACKET = 72, + /** '\' key. */ + AKEYCODE_BACKSLASH = 73, + /** ';' key. */ + AKEYCODE_SEMICOLON = 74, + /** ''' (apostrophe) key. */ + AKEYCODE_APOSTROPHE = 75, + /** '/' key. */ + AKEYCODE_SLASH = 76, + /** '@' key. */ + AKEYCODE_AT = 77, + /** Number modifier key. + * Used to enter numeric symbols. + * This key is not {@link AKEYCODE_NUM_LOCK}; it is more like {@link AKEYCODE_ALT_LEFT}. */ + AKEYCODE_NUM = 78, + /** Headset Hook key. + * Used to hang up calls and stop media. */ + AKEYCODE_HEADSETHOOK = 79, + /** Camera Focus key. + * Used to focus the camera. */ + AKEYCODE_FOCUS = 80, + /** '+' key. */ + AKEYCODE_PLUS = 81, + /** Menu key. */ + AKEYCODE_MENU = 82, + /** Notification key. */ + AKEYCODE_NOTIFICATION = 83, + /** Search key. */ + AKEYCODE_SEARCH = 84, + /** Play/Pause media key. */ + AKEYCODE_MEDIA_PLAY_PAUSE= 85, + /** Stop media key. */ + AKEYCODE_MEDIA_STOP = 86, + /** Play Next media key. */ + AKEYCODE_MEDIA_NEXT = 87, + /** Play Previous media key. */ + AKEYCODE_MEDIA_PREVIOUS = 88, + /** Rewind media key. */ + AKEYCODE_MEDIA_REWIND = 89, + /** Fast Forward media key. */ + AKEYCODE_MEDIA_FAST_FORWARD = 90, + /** Mute key. + * Mutes the microphone, unlike {@link AKEYCODE_VOLUME_MUTE}. */ + AKEYCODE_MUTE = 91, + /** Page Up key. */ + AKEYCODE_PAGE_UP = 92, + /** Page Down key. */ + AKEYCODE_PAGE_DOWN = 93, + /** Picture Symbols modifier key. + * Used to switch symbol sets (Emoji, Kao-moji). */ + AKEYCODE_PICTSYMBOLS = 94, + /** Switch Charset modifier key. + * Used to switch character sets (Kanji, Katakana). */ + AKEYCODE_SWITCH_CHARSET = 95, + /** A Button key. + * On a game controller, the A button should be either the button labeled A + * or the first button on the bottom row of controller buttons. */ + AKEYCODE_BUTTON_A = 96, + /** B Button key. + * On a game controller, the B button should be either the button labeled B + * or the second button on the bottom row of controller buttons. */ + AKEYCODE_BUTTON_B = 97, + /** C Button key. + * On a game controller, the C button should be either the button labeled C + * or the third button on the bottom row of controller buttons. */ + AKEYCODE_BUTTON_C = 98, + /** X Button key. + * On a game controller, the X button should be either the button labeled X + * or the first button on the upper row of controller buttons. */ + AKEYCODE_BUTTON_X = 99, + /** Y Button key. + * On a game controller, the Y button should be either the button labeled Y + * or the second button on the upper row of controller buttons. */ + AKEYCODE_BUTTON_Y = 100, + /** Z Button key. + * On a game controller, the Z button should be either the button labeled Z + * or the third button on the upper row of controller buttons. */ + AKEYCODE_BUTTON_Z = 101, + /** L1 Button key. + * On a game controller, the L1 button should be either the button labeled L1 (or L) + * or the top left trigger button. */ + AKEYCODE_BUTTON_L1 = 102, + /** R1 Button key. + * On a game controller, the R1 button should be either the button labeled R1 (or R) + * or the top right trigger button. */ + AKEYCODE_BUTTON_R1 = 103, + /** L2 Button key. + * On a game controller, the L2 button should be either the button labeled L2 + * or the bottom left trigger button. */ + AKEYCODE_BUTTON_L2 = 104, + /** R2 Button key. + * On a game controller, the R2 button should be either the button labeled R2 + * or the bottom right trigger button. */ + AKEYCODE_BUTTON_R2 = 105, + /** Left Thumb Button key. + * On a game controller, the left thumb button indicates that the left (or only) + * joystick is pressed. */ + AKEYCODE_BUTTON_THUMBL = 106, + /** Right Thumb Button key. + * On a game controller, the right thumb button indicates that the right + * joystick is pressed. */ + AKEYCODE_BUTTON_THUMBR = 107, + /** Start Button key. + * On a game controller, the button labeled Start. */ + AKEYCODE_BUTTON_START = 108, + /** Select Button key. + * On a game controller, the button labeled Select. */ + AKEYCODE_BUTTON_SELECT = 109, + /** Mode Button key. + * On a game controller, the button labeled Mode. */ + AKEYCODE_BUTTON_MODE = 110, + /** Escape key. */ + AKEYCODE_ESCAPE = 111, + /** Forward Delete key. + * Deletes characters ahead of the insertion point, unlike {@link AKEYCODE_DEL}. */ + AKEYCODE_FORWARD_DEL = 112, + /** Left Control modifier key. */ + AKEYCODE_CTRL_LEFT = 113, + /** Right Control modifier key. */ + AKEYCODE_CTRL_RIGHT = 114, + /** Caps Lock key. */ + AKEYCODE_CAPS_LOCK = 115, + /** Scroll Lock key. */ + AKEYCODE_SCROLL_LOCK = 116, + /** Left Meta modifier key. */ + AKEYCODE_META_LEFT = 117, + /** Right Meta modifier key. */ + AKEYCODE_META_RIGHT = 118, + /** Function modifier key. */ + AKEYCODE_FUNCTION = 119, + /** System Request / Print Screen key. */ + AKEYCODE_SYSRQ = 120, + /** Break / Pause key. */ + AKEYCODE_BREAK = 121, + /** Home Movement key. + * Used for scrolling or moving the cursor around to the start of a line + * or to the top of a list. */ + AKEYCODE_MOVE_HOME = 122, + /** End Movement key. + * Used for scrolling or moving the cursor around to the end of a line + * or to the bottom of a list. */ + AKEYCODE_MOVE_END = 123, + /** Insert key. + * Toggles insert / overwrite edit mode. */ + AKEYCODE_INSERT = 124, + /** Forward key. + * Navigates forward in the history stack. Complement of {@link AKEYCODE_BACK}. */ + AKEYCODE_FORWARD = 125, + /** Play media key. */ + AKEYCODE_MEDIA_PLAY = 126, + /** Pause media key. */ + AKEYCODE_MEDIA_PAUSE = 127, + /** Close media key. + * May be used to close a CD tray, for example. */ + AKEYCODE_MEDIA_CLOSE = 128, + /** Eject media key. + * May be used to eject a CD tray, for example. */ + AKEYCODE_MEDIA_EJECT = 129, + /** Record media key. */ + AKEYCODE_MEDIA_RECORD = 130, + /** F1 key. */ + AKEYCODE_F1 = 131, + /** F2 key. */ + AKEYCODE_F2 = 132, + /** F3 key. */ + AKEYCODE_F3 = 133, + /** F4 key. */ + AKEYCODE_F4 = 134, + /** F5 key. */ + AKEYCODE_F5 = 135, + /** F6 key. */ + AKEYCODE_F6 = 136, + /** F7 key. */ + AKEYCODE_F7 = 137, + /** F8 key. */ + AKEYCODE_F8 = 138, + /** F9 key. */ + AKEYCODE_F9 = 139, + /** F10 key. */ + AKEYCODE_F10 = 140, + /** F11 key. */ + AKEYCODE_F11 = 141, + /** F12 key. */ + AKEYCODE_F12 = 142, + /** Num Lock key. + * This is the Num Lock key; it is different from {@link AKEYCODE_NUM}. + * This key alters the behavior of other keys on the numeric keypad. */ + AKEYCODE_NUM_LOCK = 143, + /** Numeric keypad '0' key. */ + AKEYCODE_NUMPAD_0 = 144, + /** Numeric keypad '1' key. */ + AKEYCODE_NUMPAD_1 = 145, + /** Numeric keypad '2' key. */ + AKEYCODE_NUMPAD_2 = 146, + /** Numeric keypad '3' key. */ + AKEYCODE_NUMPAD_3 = 147, + /** Numeric keypad '4' key. */ + AKEYCODE_NUMPAD_4 = 148, + /** Numeric keypad '5' key. */ + AKEYCODE_NUMPAD_5 = 149, + /** Numeric keypad '6' key. */ + AKEYCODE_NUMPAD_6 = 150, + /** Numeric keypad '7' key. */ + AKEYCODE_NUMPAD_7 = 151, + /** Numeric keypad '8' key. */ + AKEYCODE_NUMPAD_8 = 152, + /** Numeric keypad '9' key. */ + AKEYCODE_NUMPAD_9 = 153, + /** Numeric keypad '/' key (for division). */ + AKEYCODE_NUMPAD_DIVIDE = 154, + /** Numeric keypad '*' key (for multiplication). */ + AKEYCODE_NUMPAD_MULTIPLY = 155, + /** Numeric keypad '-' key (for subtraction). */ + AKEYCODE_NUMPAD_SUBTRACT = 156, + /** Numeric keypad '+' key (for addition). */ + AKEYCODE_NUMPAD_ADD = 157, + /** Numeric keypad '.' key (for decimals or digit grouping). */ + AKEYCODE_NUMPAD_DOT = 158, + /** Numeric keypad ',' key (for decimals or digit grouping). */ + AKEYCODE_NUMPAD_COMMA = 159, + /** Numeric keypad Enter key. */ + AKEYCODE_NUMPAD_ENTER = 160, + /** Numeric keypad '=' key. */ + AKEYCODE_NUMPAD_EQUALS = 161, + /** Numeric keypad '(' key. */ + AKEYCODE_NUMPAD_LEFT_PAREN = 162, + /** Numeric keypad ')' key. */ + AKEYCODE_NUMPAD_RIGHT_PAREN = 163, + /** Volume Mute key. + * Mutes the speaker, unlike {@link AKEYCODE_MUTE}. + * This key should normally be implemented as a toggle such that the first press + * mutes the speaker and the second press restores the original volume. */ + AKEYCODE_VOLUME_MUTE = 164, + /** Info key. + * Common on TV remotes to show additional information related to what is + * currently being viewed. */ + AKEYCODE_INFO = 165, + /** Channel up key. + * On TV remotes, increments the television channel. */ + AKEYCODE_CHANNEL_UP = 166, + /** Channel down key. + * On TV remotes, decrements the television channel. */ + AKEYCODE_CHANNEL_DOWN = 167, + /** Zoom in key. */ + AKEYCODE_ZOOM_IN = 168, + /** Zoom out key. */ + AKEYCODE_ZOOM_OUT = 169, + /** TV key. + * On TV remotes, switches to viewing live TV. */ + AKEYCODE_TV = 170, + /** Window key. + * On TV remotes, toggles picture-in-picture mode or other windowing functions. */ + AKEYCODE_WINDOW = 171, + /** Guide key. + * On TV remotes, shows a programming guide. */ + AKEYCODE_GUIDE = 172, + /** DVR key. + * On some TV remotes, switches to a DVR mode for recorded shows. */ + AKEYCODE_DVR = 173, + /** Bookmark key. + * On some TV remotes, bookmarks content or web pages. */ + AKEYCODE_BOOKMARK = 174, + /** Toggle captions key. + * Switches the mode for closed-captioning text, for example during television shows. */ + AKEYCODE_CAPTIONS = 175, + /** Settings key. + * Starts the system settings activity. */ + AKEYCODE_SETTINGS = 176, + /** TV power key. + * On TV remotes, toggles the power on a television screen. */ + AKEYCODE_TV_POWER = 177, + /** TV input key. + * On TV remotes, switches the input on a television screen. */ + AKEYCODE_TV_INPUT = 178, + /** Set-top-box power key. + * On TV remotes, toggles the power on an external Set-top-box. */ + AKEYCODE_STB_POWER = 179, + /** Set-top-box input key. + * On TV remotes, switches the input mode on an external Set-top-box. */ + AKEYCODE_STB_INPUT = 180, + /** A/V Receiver power key. + * On TV remotes, toggles the power on an external A/V Receiver. */ + AKEYCODE_AVR_POWER = 181, + /** A/V Receiver input key. + * On TV remotes, switches the input mode on an external A/V Receiver. */ + AKEYCODE_AVR_INPUT = 182, + /** Red "programmable" key. + * On TV remotes, acts as a contextual/programmable key. */ + AKEYCODE_PROG_RED = 183, + /** Green "programmable" key. + * On TV remotes, actsas a contextual/programmable key. */ + AKEYCODE_PROG_GREEN = 184, + /** Yellow "programmable" key. + * On TV remotes, acts as a contextual/programmable key. */ + AKEYCODE_PROG_YELLOW = 185, + /** Blue "programmable" key. + * On TV remotes, acts as a contextual/programmable key. */ + AKEYCODE_PROG_BLUE = 186, + /** App switch key. + * Should bring up the application switcher dialog. */ + AKEYCODE_APP_SWITCH = 187, + /** Generic Game Pad Button #1.*/ + AKEYCODE_BUTTON_1 = 188, + /** Generic Game Pad Button #2.*/ + AKEYCODE_BUTTON_2 = 189, + /** Generic Game Pad Button #3.*/ + AKEYCODE_BUTTON_3 = 190, + /** Generic Game Pad Button #4.*/ + AKEYCODE_BUTTON_4 = 191, + /** Generic Game Pad Button #5.*/ + AKEYCODE_BUTTON_5 = 192, + /** Generic Game Pad Button #6.*/ + AKEYCODE_BUTTON_6 = 193, + /** Generic Game Pad Button #7.*/ + AKEYCODE_BUTTON_7 = 194, + /** Generic Game Pad Button #8.*/ + AKEYCODE_BUTTON_8 = 195, + /** Generic Game Pad Button #9.*/ + AKEYCODE_BUTTON_9 = 196, + /** Generic Game Pad Button #10.*/ + AKEYCODE_BUTTON_10 = 197, + /** Generic Game Pad Button #11.*/ + AKEYCODE_BUTTON_11 = 198, + /** Generic Game Pad Button #12.*/ + AKEYCODE_BUTTON_12 = 199, + /** Generic Game Pad Button #13.*/ + AKEYCODE_BUTTON_13 = 200, + /** Generic Game Pad Button #14.*/ + AKEYCODE_BUTTON_14 = 201, + /** Generic Game Pad Button #15.*/ + AKEYCODE_BUTTON_15 = 202, + /** Generic Game Pad Button #16.*/ + AKEYCODE_BUTTON_16 = 203, + /** Language Switch key. + * Toggles the current input language such as switching between English and Japanese on + * a QWERTY keyboard. On some devices, the same function may be performed by + * pressing Shift+Spacebar. */ + AKEYCODE_LANGUAGE_SWITCH = 204, + /** Manner Mode key. + * Toggles silent or vibrate mode on and off to make the device behave more politely + * in certain settings such as on a crowded train. On some devices, the key may only + * operate when long-pressed. */ + AKEYCODE_MANNER_MODE = 205, + /** 3D Mode key. + * Toggles the display between 2D and 3D mode. */ + AKEYCODE_3D_MODE = 206, + /** Contacts special function key. + * Used to launch an address book application. */ + AKEYCODE_CONTACTS = 207, + /** Calendar special function key. + * Used to launch a calendar application. */ + AKEYCODE_CALENDAR = 208, + /** Music special function key. + * Used to launch a music player application. */ + AKEYCODE_MUSIC = 209, + /** Calculator special function key. + * Used to launch a calculator application. */ + AKEYCODE_CALCULATOR = 210, + /** Japanese full-width / half-width key. */ + AKEYCODE_ZENKAKU_HANKAKU = 211, + /** Japanese alphanumeric key. */ + AKEYCODE_EISU = 212, + /** Japanese non-conversion key. */ + AKEYCODE_MUHENKAN = 213, + /** Japanese conversion key. */ + AKEYCODE_HENKAN = 214, + /** Japanese katakana / hiragana key. */ + AKEYCODE_KATAKANA_HIRAGANA = 215, + /** Japanese Yen key. */ + AKEYCODE_YEN = 216, + /** Japanese Ro key. */ + AKEYCODE_RO = 217, + /** Japanese kana key. */ + AKEYCODE_KANA = 218, + /** Assist key. + * Launches the global assist activity. Not delivered to applications. */ + AKEYCODE_ASSIST = 219, + /** Brightness Down key. + * Adjusts the screen brightness down. */ + AKEYCODE_BRIGHTNESS_DOWN = 220, + /** Brightness Up key. + * Adjusts the screen brightness up. */ + AKEYCODE_BRIGHTNESS_UP = 221, + /** Audio Track key. + * Switches the audio tracks. */ + AKEYCODE_MEDIA_AUDIO_TRACK = 222, + /** Sleep key. + * Puts the device to sleep. Behaves somewhat like {@link AKEYCODE_POWER} but it + * has no effect if the device is already asleep. */ + AKEYCODE_SLEEP = 223, + /** Wakeup key. + * Wakes up the device. Behaves somewhat like {@link AKEYCODE_POWER} but it + * has no effect if the device is already awake. */ + AKEYCODE_WAKEUP = 224, + /** Pairing key. + * Initiates peripheral pairing mode. Useful for pairing remote control + * devices or game controllers, especially if no other input mode is + * available. */ + AKEYCODE_PAIRING = 225, + /** Media Top Menu key. + * Goes to the top of media menu. */ + AKEYCODE_MEDIA_TOP_MENU = 226, + /** '11' key. */ + AKEYCODE_11 = 227, + /** '12' key. */ + AKEYCODE_12 = 228, + /** Last Channel key. + * Goes to the last viewed channel. */ + AKEYCODE_LAST_CHANNEL = 229, + /** TV data service key. + * Displays data services like weather, sports. */ + AKEYCODE_TV_DATA_SERVICE = 230, + /** Voice Assist key. + * Launches the global voice assist activity. Not delivered to applications. */ + AKEYCODE_VOICE_ASSIST = 231, + /** Radio key. + * Toggles TV service / Radio service. */ + AKEYCODE_TV_RADIO_SERVICE = 232, + /** Teletext key. + * Displays Teletext service. */ + AKEYCODE_TV_TELETEXT = 233, + /** Number entry key. + * Initiates to enter multi-digit channel nubmber when each digit key is assigned + * for selecting separate channel. Corresponds to Number Entry Mode (0x1D) of CEC + * User Control Code. */ + AKEYCODE_TV_NUMBER_ENTRY = 234, + /** Analog Terrestrial key. + * Switches to analog terrestrial broadcast service. */ + AKEYCODE_TV_TERRESTRIAL_ANALOG = 235, + /** Digital Terrestrial key. + * Switches to digital terrestrial broadcast service. */ + AKEYCODE_TV_TERRESTRIAL_DIGITAL = 236, + /** Satellite key. + * Switches to digital satellite broadcast service. */ + AKEYCODE_TV_SATELLITE = 237, + /** BS key. + * Switches to BS digital satellite broadcasting service available in Japan. */ + AKEYCODE_TV_SATELLITE_BS = 238, + /** CS key. + * Switches to CS digital satellite broadcasting service available in Japan. */ + AKEYCODE_TV_SATELLITE_CS = 239, + /** BS/CS key. + * Toggles between BS and CS digital satellite services. */ + AKEYCODE_TV_SATELLITE_SERVICE = 240, + /** Toggle Network key. + * Toggles selecting broacast services. */ + AKEYCODE_TV_NETWORK = 241, + /** Antenna/Cable key. + * Toggles broadcast input source between antenna and cable. */ + AKEYCODE_TV_ANTENNA_CABLE = 242, + /** HDMI #1 key. + * Switches to HDMI input #1. */ + AKEYCODE_TV_INPUT_HDMI_1 = 243, + /** HDMI #2 key. + * Switches to HDMI input #2. */ + AKEYCODE_TV_INPUT_HDMI_2 = 244, + /** HDMI #3 key. + * Switches to HDMI input #3. */ + AKEYCODE_TV_INPUT_HDMI_3 = 245, + /** HDMI #4 key. + * Switches to HDMI input #4. */ + AKEYCODE_TV_INPUT_HDMI_4 = 246, + /** Composite #1 key. + * Switches to composite video input #1. */ + AKEYCODE_TV_INPUT_COMPOSITE_1 = 247, + /** Composite #2 key. + * Switches to composite video input #2. */ + AKEYCODE_TV_INPUT_COMPOSITE_2 = 248, + /** Component #1 key. + * Switches to component video input #1. */ + AKEYCODE_TV_INPUT_COMPONENT_1 = 249, + /** Component #2 key. + * Switches to component video input #2. */ + AKEYCODE_TV_INPUT_COMPONENT_2 = 250, + /** VGA #1 key. + * Switches to VGA (analog RGB) input #1. */ + AKEYCODE_TV_INPUT_VGA_1 = 251, + /** Audio description key. + * Toggles audio description off / on. */ + AKEYCODE_TV_AUDIO_DESCRIPTION = 252, + /** Audio description mixing volume up key. + * Louden audio description volume as compared with normal audio volume. */ + AKEYCODE_TV_AUDIO_DESCRIPTION_MIX_UP = 253, + /** Audio description mixing volume down key. + * Lessen audio description volume as compared with normal audio volume. */ + AKEYCODE_TV_AUDIO_DESCRIPTION_MIX_DOWN = 254, + /** Zoom mode key. + * Changes Zoom mode (Normal, Full, Zoom, Wide-zoom, etc.) */ + AKEYCODE_TV_ZOOM_MODE = 255, + /** Contents menu key. + * Goes to the title list. Corresponds to Contents Menu (0x0B) of CEC User Control + * Code */ + AKEYCODE_TV_CONTENTS_MENU = 256, + /** Media context menu key. + * Goes to the context menu of media contents. Corresponds to Media Context-sensitive + * Menu (0x11) of CEC User Control Code. */ + AKEYCODE_TV_MEDIA_CONTEXT_MENU = 257, + /** Timer programming key. + * Goes to the timer recording menu. Corresponds to Timer Programming (0x54) of + * CEC User Control Code. */ + AKEYCODE_TV_TIMER_PROGRAMMING = 258, + /** Help key. */ + AKEYCODE_HELP = 259, + AKEYCODE_NAVIGATE_PREVIOUS = 260, + AKEYCODE_NAVIGATE_NEXT = 261, + AKEYCODE_NAVIGATE_IN = 262, + AKEYCODE_NAVIGATE_OUT = 263, + /** Primary stem key for Wear + * Main power/reset button on watch. */ + AKEYCODE_STEM_PRIMARY = 264, + /** Generic stem key 1 for Wear */ + AKEYCODE_STEM_1 = 265, + /** Generic stem key 2 for Wear */ + AKEYCODE_STEM_2 = 266, + /** Generic stem key 3 for Wear */ + AKEYCODE_STEM_3 = 267, + AKEYCODE_MEDIA_SKIP_FORWARD = 272, + AKEYCODE_MEDIA_SKIP_BACKWARD = 273, + AKEYCODE_MEDIA_STEP_FORWARD = 274, + AKEYCODE_MEDIA_STEP_BACKWARD = 275, + /** Put device to sleep unless a wakelock is held. */ + AKEYCODE_SOFT_SLEEP = 276 + + // NOTE: If you add a new keycode here you must also add it to several other files. + // Refer to frameworks/base/core/java/android/view/KeyEvent.java for the full list. +}; + +#ifdef __cplusplus +} +#endif + +#endif // _ANDROID_KEYCODES_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/looper.h b/third_party/android_frameworks_native/include/android/looper.h new file mode 100644 index 00000000000000..718f703048dcbd --- /dev/null +++ b/third_party/android_frameworks_native/include/android/looper.h @@ -0,0 +1,269 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Looper + * @{ + */ + +/** + * @file looper.h + */ + +#ifndef ANDROID_LOOPER_H +#define ANDROID_LOOPER_H + +#ifdef __cplusplus +extern "C" { +#endif + +struct ALooper; +/** + * ALooper + * + * A looper is the state tracking an event loop for a thread. + * Loopers do not define event structures or other such things; rather + * they are a lower-level facility to attach one or more discrete objects + * listening for an event. An "event" here is simply data available on + * a file descriptor: each attached object has an associated file descriptor, + * and waiting for "events" means (internally) polling on all of these file + * descriptors until one or more of them have data available. + * + * A thread can have only one ALooper associated with it. + */ +typedef struct ALooper ALooper; + +/** + * Returns the looper associated with the calling thread, or NULL if + * there is not one. + */ +ALooper* ALooper_forThread(); + +/** Option for for ALooper_prepare(). */ +enum { + /** + * This looper will accept calls to ALooper_addFd() that do not + * have a callback (that is provide NULL for the callback). In + * this case the caller of ALooper_pollOnce() or ALooper_pollAll() + * MUST check the return from these functions to discover when + * data is available on such fds and process it. + */ + ALOOPER_PREPARE_ALLOW_NON_CALLBACKS = 1<<0 +}; + +/** + * Prepares a looper associated with the calling thread, and returns it. + * If the thread already has a looper, it is returned. Otherwise, a new + * one is created, associated with the thread, and returned. + * + * The opts may be ALOOPER_PREPARE_ALLOW_NON_CALLBACKS or 0. + */ +ALooper* ALooper_prepare(int opts); + +/** Result from ALooper_pollOnce() and ALooper_pollAll(). */ +enum { + /** + * The poll was awoken using wake() before the timeout expired + * and no callbacks were executed and no other file descriptors were ready. + */ + ALOOPER_POLL_WAKE = -1, + + /** + * Result from ALooper_pollOnce() and ALooper_pollAll(): + * One or more callbacks were executed. + */ + ALOOPER_POLL_CALLBACK = -2, + + /** + * Result from ALooper_pollOnce() and ALooper_pollAll(): + * The timeout expired. + */ + ALOOPER_POLL_TIMEOUT = -3, + + /** + * Result from ALooper_pollOnce() and ALooper_pollAll(): + * An error occurred. + */ + ALOOPER_POLL_ERROR = -4, +}; + +/** + * Acquire a reference on the given ALooper object. This prevents the object + * from being deleted until the reference is removed. This is only needed + * to safely hand an ALooper from one thread to another. + */ +void ALooper_acquire(ALooper* looper); + +/** + * Remove a reference that was previously acquired with ALooper_acquire(). + */ +void ALooper_release(ALooper* looper); + +/** + * Flags for file descriptor events that a looper can monitor. + * + * These flag bits can be combined to monitor multiple events at once. + */ +enum { + /** + * The file descriptor is available for read operations. + */ + ALOOPER_EVENT_INPUT = 1 << 0, + + /** + * The file descriptor is available for write operations. + */ + ALOOPER_EVENT_OUTPUT = 1 << 1, + + /** + * The file descriptor has encountered an error condition. + * + * The looper always sends notifications about errors; it is not necessary + * to specify this event flag in the requested event set. + */ + ALOOPER_EVENT_ERROR = 1 << 2, + + /** + * The file descriptor was hung up. + * For example, indicates that the remote end of a pipe or socket was closed. + * + * The looper always sends notifications about hangups; it is not necessary + * to specify this event flag in the requested event set. + */ + ALOOPER_EVENT_HANGUP = 1 << 3, + + /** + * The file descriptor is invalid. + * For example, the file descriptor was closed prematurely. + * + * The looper always sends notifications about invalid file descriptors; it is not necessary + * to specify this event flag in the requested event set. + */ + ALOOPER_EVENT_INVALID = 1 << 4, +}; + +/** + * For callback-based event loops, this is the prototype of the function + * that is called when a file descriptor event occurs. + * It is given the file descriptor it is associated with, + * a bitmask of the poll events that were triggered (typically ALOOPER_EVENT_INPUT), + * and the data pointer that was originally supplied. + * + * Implementations should return 1 to continue receiving callbacks, or 0 + * to have this file descriptor and callback unregistered from the looper. + */ +typedef int (*ALooper_callbackFunc)(int fd, int events, void* data); + +/** + * Waits for events to be available, with optional timeout in milliseconds. + * Invokes callbacks for all file descriptors on which an event occurred. + * + * If the timeout is zero, returns immediately without blocking. + * If the timeout is negative, waits indefinitely until an event appears. + * + * Returns ALOOPER_POLL_WAKE if the poll was awoken using wake() before + * the timeout expired and no callbacks were invoked and no other file + * descriptors were ready. + * + * Returns ALOOPER_POLL_CALLBACK if one or more callbacks were invoked. + * + * Returns ALOOPER_POLL_TIMEOUT if there was no data before the given + * timeout expired. + * + * Returns ALOOPER_POLL_ERROR if an error occurred. + * + * Returns a value >= 0 containing an identifier (the same identifier + * `ident` passed to ALooper_addFd()) if its file descriptor has data + * and it has no callback function (requiring the caller here to + * handle it). In this (and only this) case outFd, outEvents and + * outData will contain the poll events and data associated with the + * fd, otherwise they will be set to NULL. + * + * This method does not return until it has finished invoking the appropriate callbacks + * for all file descriptors that were signalled. + */ +int ALooper_pollOnce(int timeoutMillis, int* outFd, int* outEvents, void** outData); + +/** + * Like ALooper_pollOnce(), but performs all pending callbacks until all + * data has been consumed or a file descriptor is available with no callback. + * This function will never return ALOOPER_POLL_CALLBACK. + */ +int ALooper_pollAll(int timeoutMillis, int* outFd, int* outEvents, void** outData); + +/** + * Wakes the poll asynchronously. + * + * This method can be called on any thread. + * This method returns immediately. + */ +void ALooper_wake(ALooper* looper); + +/** + * Adds a new file descriptor to be polled by the looper. + * If the same file descriptor was previously added, it is replaced. + * + * "fd" is the file descriptor to be added. + * "ident" is an identifier for this event, which is returned from ALooper_pollOnce(). + * The identifier must be >= 0, or ALOOPER_POLL_CALLBACK if providing a non-NULL callback. + * "events" are the poll events to wake up on. Typically this is ALOOPER_EVENT_INPUT. + * "callback" is the function to call when there is an event on the file descriptor. + * "data" is a private data pointer to supply to the callback. + * + * There are two main uses of this function: + * + * (1) If "callback" is non-NULL, then this function will be called when there is + * data on the file descriptor. It should execute any events it has pending, + * appropriately reading from the file descriptor. The 'ident' is ignored in this case. + * + * (2) If "callback" is NULL, the 'ident' will be returned by ALooper_pollOnce + * when its file descriptor has data available, requiring the caller to take + * care of processing it. + * + * Returns 1 if the file descriptor was added or -1 if an error occurred. + * + * This method can be called on any thread. + * This method may block briefly if it needs to wake the poll. + */ +int ALooper_addFd(ALooper* looper, int fd, int ident, int events, + ALooper_callbackFunc callback, void* data); + +/** + * Removes a previously added file descriptor from the looper. + * + * When this method returns, it is safe to close the file descriptor since the looper + * will no longer have a reference to it. However, it is possible for the callback to + * already be running or for it to run one last time if the file descriptor was already + * signalled. Calling code is responsible for ensuring that this case is safely handled. + * For example, if the callback takes care of removing itself during its own execution either + * by returning 0 or by calling this method, then it can be guaranteed to not be invoked + * again at any later time unless registered anew. + * + * Returns 1 if the file descriptor was removed, 0 if none was previously registered + * or -1 if an error occurred. + * + * This method can be called on any thread. + * This method may block briefly if it needs to wake the poll. + */ +int ALooper_removeFd(ALooper* looper, int fd); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_LOOPER_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/multinetwork.h b/third_party/android_frameworks_native/include/android/multinetwork.h new file mode 100644 index 00000000000000..6c718c9037da6b --- /dev/null +++ b/third_party/android_frameworks_native/include/android/multinetwork.h @@ -0,0 +1,109 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_MULTINETWORK_H +#define ANDROID_MULTINETWORK_H + +#include +#include +#include + +__BEGIN_DECLS + +/** + * The corresponding C type for android.net.Network#getNetworkHandle() return + * values. The Java signed long value can be safely cast to a net_handle_t: + * + * [C] ((net_handle_t) java_long_network_handle) + * [C++] static_cast(java_long_network_handle) + * + * as appropriate. + */ +typedef uint64_t net_handle_t; + +/** + * The value NETWORK_UNSPECIFIED indicates no specific network. + * + * For some functions (documented below), a previous binding may be cleared + * by an invocation with NETWORK_UNSPECIFIED. + * + * Depending on the context it may indicate an error. It is expressly + * not used to indicate some notion of the "current default network". + */ +#define NETWORK_UNSPECIFIED ((net_handle_t)0) + + +/** + * All functions below that return an int return 0 on success or -1 + * on failure with an appropriate errno value set. + */ + + +/** + * Set the network to be used by the given socket file descriptor. + * + * To clear a previous socket binding invoke with NETWORK_UNSPECIFIED. + * + * This is the equivalent of: + * + * [ android.net.Network#bindSocket() ] + * https://developer.android.com/reference/android/net/Network.html#bindSocket(java.net.Socket) + */ +int android_setsocknetwork(net_handle_t network, int fd); + + +/** + * Binds the current process to |network|. All sockets created in the future + * (and not explicitly bound via android_setsocknetwork()) will be bound to + * |network|. All host name resolutions will be limited to |network| as well. + * Note that if the network identified by |network| ever disconnects, all + * sockets created in this way will cease to work and all host name + * resolutions will fail. This is by design so an application doesn't + * accidentally use sockets it thinks are still bound to a particular network. + * + * To clear a previous process binding invoke with NETWORK_UNSPECIFIED. + * + * This is the equivalent of: + * + * [ android.net.ConnectivityManager#setProcessDefaultNetwork() ] + * https://developer.android.com/reference/android/net/ConnectivityManager.html#setProcessDefaultNetwork(android.net.Network) + */ +int android_setprocnetwork(net_handle_t network); + + +/** + * Perform hostname resolution via the DNS servers associated with |network|. + * + * All arguments (apart from |network|) are used identically as those passed + * to getaddrinfo(3). Return and error values are identical to those of + * getaddrinfo(3), and in particular gai_strerror(3) can be used as expected. + * Similar to getaddrinfo(3): + * - |hints| may be NULL (in which case man page documented defaults apply) + * - either |node| or |service| may be NULL, but not both + * - |res| must not be NULL + * + * This is the equivalent of: + * + * [ android.net.Network#getAllByName() ] + * https://developer.android.com/reference/android/net/Network.html#getAllByName(java.lang.String) + */ +int android_getaddrinfofornetwork(net_handle_t network, + const char *node, const char *service, + const struct addrinfo *hints, struct addrinfo **res); + +__END_DECLS + +#endif // ANDROID_MULTINETWORK_H diff --git a/third_party/android_frameworks_native/include/android/native_activity.h b/third_party/android_frameworks_native/include/android/native_activity.h new file mode 100644 index 00000000000000..d3d99cf7a9b95e --- /dev/null +++ b/third_party/android_frameworks_native/include/android/native_activity.h @@ -0,0 +1,340 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup NativeActivity Native Activity + * @{ + */ + +/** + * @file native_activity.h + */ + +#ifndef ANDROID_NATIVE_ACTIVITY_H +#define ANDROID_NATIVE_ACTIVITY_H + +#include +#include + +#include + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * {@link ANativeActivityCallbacks} + */ +struct ANativeActivityCallbacks; + +/** + * This structure defines the native side of an android.app.NativeActivity. + * It is created by the framework, and handed to the application's native + * code as it is being launched. + */ +typedef struct ANativeActivity { + /** + * Pointer to the callback function table of the native application. + * You can set the functions here to your own callbacks. The callbacks + * pointer itself here should not be changed; it is allocated and managed + * for you by the framework. + */ + struct ANativeActivityCallbacks* callbacks; + + /** + * The global handle on the process's Java VM. + */ + JavaVM* vm; + + /** + * JNI context for the main thread of the app. Note that this field + * can ONLY be used from the main thread of the process; that is, the + * thread that calls into the ANativeActivityCallbacks. + */ + JNIEnv* env; + + /** + * The NativeActivity object handle. + * + * IMPORTANT NOTE: This member is mis-named. It should really be named + * 'activity' instead of 'clazz', since it's a reference to the + * NativeActivity instance created by the system for you. + * + * We unfortunately cannot change this without breaking NDK + * source-compatibility. + */ + jobject clazz; + + /** + * Path to this application's internal data directory. + */ + const char* internalDataPath; + + /** + * Path to this application's external (removable/mountable) data directory. + */ + const char* externalDataPath; + + /** + * The platform's SDK version code. + */ + int32_t sdkVersion; + + /** + * This is the native instance of the application. It is not used by + * the framework, but can be set by the application to its own instance + * state. + */ + void* instance; + + /** + * Pointer to the Asset Manager instance for the application. The application + * uses this to access binary assets bundled inside its own .apk file. + */ + AAssetManager* assetManager; + + /** + * Available starting with Honeycomb: path to the directory containing + * the application's OBB files (if any). If the app doesn't have any + * OBB files, this directory may not exist. + */ + const char* obbPath; +} ANativeActivity; + +/** + * These are the callbacks the framework makes into a native application. + * All of these callbacks happen on the main thread of the application. + * By default, all callbacks are NULL; set to a pointer to your own function + * to have it called. + */ +typedef struct ANativeActivityCallbacks { + /** + * NativeActivity has started. See Java documentation for Activity.onStart() + * for more information. + */ + void (*onStart)(ANativeActivity* activity); + + /** + * NativeActivity has resumed. See Java documentation for Activity.onResume() + * for more information. + */ + void (*onResume)(ANativeActivity* activity); + + /** + * Framework is asking NativeActivity to save its current instance state. + * See Java documentation for Activity.onSaveInstanceState() for more + * information. The returned pointer needs to be created with malloc(); + * the framework will call free() on it for you. You also must fill in + * outSize with the number of bytes in the allocation. Note that the + * saved state will be persisted, so it can not contain any active + * entities (pointers to memory, file descriptors, etc). + */ + void* (*onSaveInstanceState)(ANativeActivity* activity, size_t* outSize); + + /** + * NativeActivity has paused. See Java documentation for Activity.onPause() + * for more information. + */ + void (*onPause)(ANativeActivity* activity); + + /** + * NativeActivity has stopped. See Java documentation for Activity.onStop() + * for more information. + */ + void (*onStop)(ANativeActivity* activity); + + /** + * NativeActivity is being destroyed. See Java documentation for Activity.onDestroy() + * for more information. + */ + void (*onDestroy)(ANativeActivity* activity); + + /** + * Focus has changed in this NativeActivity's window. This is often used, + * for example, to pause a game when it loses input focus. + */ + void (*onWindowFocusChanged)(ANativeActivity* activity, int hasFocus); + + /** + * The drawing window for this native activity has been created. You + * can use the given native window object to start drawing. + */ + void (*onNativeWindowCreated)(ANativeActivity* activity, ANativeWindow* window); + + /** + * The drawing window for this native activity has been resized. You should + * retrieve the new size from the window and ensure that your rendering in + * it now matches. + */ + void (*onNativeWindowResized)(ANativeActivity* activity, ANativeWindow* window); + + /** + * The drawing window for this native activity needs to be redrawn. To avoid + * transient artifacts during screen changes (such resizing after rotation), + * applications should not return from this function until they have finished + * drawing their window in its current state. + */ + void (*onNativeWindowRedrawNeeded)(ANativeActivity* activity, ANativeWindow* window); + + /** + * The drawing window for this native activity is going to be destroyed. + * You MUST ensure that you do not touch the window object after returning + * from this function: in the common case of drawing to the window from + * another thread, that means the implementation of this callback must + * properly synchronize with the other thread to stop its drawing before + * returning from here. + */ + void (*onNativeWindowDestroyed)(ANativeActivity* activity, ANativeWindow* window); + + /** + * The input queue for this native activity's window has been created. + * You can use the given input queue to start retrieving input events. + */ + void (*onInputQueueCreated)(ANativeActivity* activity, AInputQueue* queue); + + /** + * The input queue for this native activity's window is being destroyed. + * You should no longer try to reference this object upon returning from this + * function. + */ + void (*onInputQueueDestroyed)(ANativeActivity* activity, AInputQueue* queue); + + /** + * The rectangle in the window in which content should be placed has changed. + */ + void (*onContentRectChanged)(ANativeActivity* activity, const ARect* rect); + + /** + * The current device AConfiguration has changed. The new configuration can + * be retrieved from assetManager. + */ + void (*onConfigurationChanged)(ANativeActivity* activity); + + /** + * The system is running low on memory. Use this callback to release + * resources you do not need, to help the system avoid killing more + * important processes. + */ + void (*onLowMemory)(ANativeActivity* activity); +} ANativeActivityCallbacks; + +/** + * This is the function that must be in the native code to instantiate the + * application's native activity. It is called with the activity instance (see + * above); if the code is being instantiated from a previously saved instance, + * the savedState will be non-NULL and point to the saved data. You must make + * any copy of this data you need -- it will be released after you return from + * this function. + */ +typedef void ANativeActivity_createFunc(ANativeActivity* activity, + void* savedState, size_t savedStateSize); + +/** + * The name of the function that NativeInstance looks for when launching its + * native code. This is the default function that is used, you can specify + * "android.app.func_name" string meta-data in your manifest to use a different + * function. + */ +extern ANativeActivity_createFunc ANativeActivity_onCreate; + +/** + * Finish the given activity. Its finish() method will be called, causing it + * to be stopped and destroyed. Note that this method can be called from + * *any* thread; it will send a message to the main thread of the process + * where the Java finish call will take place. + */ +void ANativeActivity_finish(ANativeActivity* activity); + +/** + * Change the window format of the given activity. Calls getWindow().setFormat() + * of the given activity. Note that this method can be called from + * *any* thread; it will send a message to the main thread of the process + * where the Java finish call will take place. + */ +void ANativeActivity_setWindowFormat(ANativeActivity* activity, int32_t format); + +/** + * Change the window flags of the given activity. Calls getWindow().setFlags() + * of the given activity. Note that this method can be called from + * *any* thread; it will send a message to the main thread of the process + * where the Java finish call will take place. See window.h for flag constants. + */ +void ANativeActivity_setWindowFlags(ANativeActivity* activity, + uint32_t addFlags, uint32_t removeFlags); + +/** + * Flags for ANativeActivity_showSoftInput; see the Java InputMethodManager + * API for documentation. + */ +enum { + /** + * Implicit request to show the input window, not as the result + * of a direct request by the user. + */ + ANATIVEACTIVITY_SHOW_SOFT_INPUT_IMPLICIT = 0x0001, + + /** + * The user has forced the input method open (such as by + * long-pressing menu) so it should not be closed until they + * explicitly do so. + */ + ANATIVEACTIVITY_SHOW_SOFT_INPUT_FORCED = 0x0002, +}; + +/** + * Show the IME while in the given activity. Calls InputMethodManager.showSoftInput() + * for the given activity. Note that this method can be called from + * *any* thread; it will send a message to the main thread of the process + * where the Java finish call will take place. + */ +void ANativeActivity_showSoftInput(ANativeActivity* activity, uint32_t flags); + +/** + * Flags for ANativeActivity_hideSoftInput; see the Java InputMethodManager + * API for documentation. + */ +enum { + /** + * The soft input window should only be hidden if it was not + * explicitly shown by the user. + */ + ANATIVEACTIVITY_HIDE_SOFT_INPUT_IMPLICIT_ONLY = 0x0001, + /** + * The soft input window should normally be hidden, unless it was + * originally shown with {@link ANATIVEACTIVITY_SHOW_SOFT_INPUT_FORCED}. + */ + ANATIVEACTIVITY_HIDE_SOFT_INPUT_NOT_ALWAYS = 0x0002, +}; + +/** + * Hide the IME while in the given activity. Calls InputMethodManager.hideSoftInput() + * for the given activity. Note that this method can be called from + * *any* thread; it will send a message to the main thread of the process + * where the Java finish call will take place. + */ +void ANativeActivity_hideSoftInput(ANativeActivity* activity, uint32_t flags); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_NATIVE_ACTIVITY_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/native_window.h b/third_party/android_frameworks_native/include/android/native_window.h new file mode 100644 index 00000000000000..cf07f1afad9856 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/native_window.h @@ -0,0 +1,150 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup NativeActivity Native Activity + * @{ + */ + +/** + * @file native_window.h + */ + +#ifndef ANDROID_NATIVE_WINDOW_H +#define ANDROID_NATIVE_WINDOW_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Pixel formats that a window can use. + */ +enum { + /** Red: 8 bits, Green: 8 bits, Blue: 8 bits, Alpha: 8 bits. **/ + WINDOW_FORMAT_RGBA_8888 = 1, + /** Red: 8 bits, Green: 8 bits, Blue: 8 bits, Unused: 8 bits. **/ + WINDOW_FORMAT_RGBX_8888 = 2, + /** Red: 5 bits, Green: 6 bits, Blue: 5 bits. **/ + WINDOW_FORMAT_RGB_565 = 4, +}; + +struct ANativeWindow; +/** + * {@link ANativeWindow} is opaque type that provides access to a native window. + * + * A pointer can be obtained using ANativeWindow_fromSurface(). + */ +typedef struct ANativeWindow ANativeWindow; + +/** + * {@link ANativeWindow} is a struct that represents a windows buffer. + * + * A pointer can be obtained using ANativeWindow_lock(). + */ +typedef struct ANativeWindow_Buffer { + // The number of pixels that are show horizontally. + int32_t width; + + // The number of pixels that are shown vertically. + int32_t height; + + // The number of *pixels* that a line in the buffer takes in + // memory. This may be >= width. + int32_t stride; + + // The format of the buffer. One of WINDOW_FORMAT_* + int32_t format; + + // The actual bits. + void* bits; + + // Do not touch. + uint32_t reserved[6]; +} ANativeWindow_Buffer; + +/** + * Acquire a reference on the given ANativeWindow object. This prevents the object + * from being deleted until the reference is removed. + */ +void ANativeWindow_acquire(ANativeWindow* window); + +/** + * Remove a reference that was previously acquired with ANativeWindow_acquire(). + */ +void ANativeWindow_release(ANativeWindow* window); + +/** + * Return the current width in pixels of the window surface. Returns a + * negative value on error. + */ +int32_t ANativeWindow_getWidth(ANativeWindow* window); + +/** + * Return the current height in pixels of the window surface. Returns a + * negative value on error. + */ +int32_t ANativeWindow_getHeight(ANativeWindow* window); + +/** + * Return the current pixel format of the window surface. Returns a + * negative value on error. + */ +int32_t ANativeWindow_getFormat(ANativeWindow* window); + +/** + * Change the format and size of the window buffers. + * + * The width and height control the number of pixels in the buffers, not the + * dimensions of the window on screen. If these are different than the + * window's physical size, then it buffer will be scaled to match that size + * when compositing it to the screen. + * + * For all of these parameters, if 0 is supplied then the window's base + * value will come back in force. + * + * width and height must be either both zero or both non-zero. + * + */ +int32_t ANativeWindow_setBuffersGeometry(ANativeWindow* window, + int32_t width, int32_t height, int32_t format); + +/** + * Lock the window's next drawing surface for writing. + * inOutDirtyBounds is used as an in/out parameter, upon entering the + * function, it contains the dirty region, that is, the region the caller + * intends to redraw. When the function returns, inOutDirtyBounds is updated + * with the actual area the caller needs to redraw -- this region is often + * extended by ANativeWindow_lock. + */ +int32_t ANativeWindow_lock(ANativeWindow* window, ANativeWindow_Buffer* outBuffer, + ARect* inOutDirtyBounds); + +/** + * Unlock the window's drawing surface after previously locking it, + * posting the new buffer to the display. + */ +int32_t ANativeWindow_unlockAndPost(ANativeWindow* window); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_NATIVE_WINDOW_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/native_window_jni.h b/third_party/android_frameworks_native/include/android/native_window_jni.h new file mode 100644 index 00000000000000..60a36c3f271076 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/native_window_jni.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup NativeActivity Native Activity + * @{ + */ + +/** + * @file native_window_jni.h + */ + +#ifndef ANDROID_NATIVE_WINDOW_JNI_H +#define ANDROID_NATIVE_WINDOW_JNI_H + +#include + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Return the ANativeWindow associated with a Java Surface object, + * for interacting with it through native code. This acquires a reference + * on the ANativeWindow that is returned; be sure to use ANativeWindow_release() + * when done with it so that it doesn't leak. + */ +ANativeWindow* ANativeWindow_fromSurface(JNIEnv* env, jobject surface); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_NATIVE_WINDOW_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/obb.h b/third_party/android_frameworks_native/include/android/obb.h new file mode 100644 index 00000000000000..4c6d9d7badd5b6 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/obb.h @@ -0,0 +1,76 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Storage + * @{ + */ + +/** + * @file obb.h + */ + +#ifndef ANDROID_OBB_H +#define ANDROID_OBB_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +struct AObbInfo; +/** {@link AObbInfo} is an opaque type representing information for obb storage. */ +typedef struct AObbInfo AObbInfo; + +/** Flag for an obb file, returned by AObbInfo_getFlags(). */ +enum { + /** overlay */ + AOBBINFO_OVERLAY = 0x0001, +}; + +/** + * Scan an OBB and get information about it. + */ +AObbInfo* AObbScanner_getObbInfo(const char* filename); + +/** + * Destroy the AObbInfo object. You must call this when finished with the object. + */ +void AObbInfo_delete(AObbInfo* obbInfo); + +/** + * Get the package name for the OBB. + */ +const char* AObbInfo_getPackageName(AObbInfo* obbInfo); + +/** + * Get the version of an OBB file. + */ +int32_t AObbInfo_getVersion(AObbInfo* obbInfo); + +/** + * Get the flags of an OBB file. + */ +int32_t AObbInfo_getFlags(AObbInfo* obbInfo); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_OBB_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/rect.h b/third_party/android_frameworks_native/include/android/rect.h new file mode 100644 index 00000000000000..80741c04420e21 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/rect.h @@ -0,0 +1,62 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup NativeActivity Native Activity + * @{ + */ + +/** + * @file rect.h + */ + +#ifndef ANDROID_RECT_H +#define ANDROID_RECT_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * {@link ARect} is a struct that represents a rectangular window area. + * + * It is used with {@link + * ANativeActivityCallbacks::onContentRectChanged} event callback and + * ANativeWindow_lock() function. + */ +typedef struct ARect { +#ifdef __cplusplus + typedef int32_t value_type; +#endif + /** left position */ + int32_t left; + /** top position */ + int32_t top; + /** left position */ + int32_t right; + /** bottom position */ + int32_t bottom; +} ARect; + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_RECT_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/sensor.h b/third_party/android_frameworks_native/include/android/sensor.h new file mode 100644 index 00000000000000..73928ea76f9925 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/sensor.h @@ -0,0 +1,475 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Sensor + * @{ + */ + +/** + * @file sensor.h + */ + +#ifndef ANDROID_SENSOR_H +#define ANDROID_SENSOR_H + +/****************************************************************** + * + * IMPORTANT NOTICE: + * + * This file is part of Android's set of stable system headers + * exposed by the Android NDK (Native Development Kit). + * + * Third-party source AND binary code relies on the definitions + * here to be FROZEN ON ALL UPCOMING PLATFORM RELEASES. + * + * - DO NOT MODIFY ENUMS (EXCEPT IF YOU ADD NEW 32-BIT VALUES) + * - DO NOT MODIFY CONSTANTS OR FUNCTIONAL MACROS + * - DO NOT CHANGE THE SIGNATURE OF FUNCTIONS IN ANY WAY + * - DO NOT CHANGE THE LAYOUT OR SIZE OF STRUCTURES + */ + +/** + * Structures and functions to receive and process sensor events in + * native code. + * + */ + +#include + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * Sensor types. + * (keep in sync with hardware/sensor.h) + */ +enum { + /** + * {@link ASENSOR_TYPE_ACCELEROMETER} + * reporting-mode: continuous + * + * All values are in SI units (m/s^2) and measure the acceleration of the + * device minus the force of gravity. + */ + ASENSOR_TYPE_ACCELEROMETER = 1, + /** + * {@link ASENSOR_TYPE_MAGNETIC_FIELD} + * reporting-mode: continuous + * + * All values are in micro-Tesla (uT) and measure the geomagnetic + * field in the X, Y and Z axis. + */ + ASENSOR_TYPE_MAGNETIC_FIELD = 2, + /** + * {@link ASENSOR_TYPE_GYROSCOPE} + * reporting-mode: continuous + * + * All values are in radians/second and measure the rate of rotation + * around the X, Y and Z axis. + */ + ASENSOR_TYPE_GYROSCOPE = 4, + /** + * {@link ASENSOR_TYPE_LIGHT} + * reporting-mode: on-change + * + * The light sensor value is returned in SI lux units. + */ + ASENSOR_TYPE_LIGHT = 5, + /** + * {@link ASENSOR_TYPE_PROXIMITY} + * reporting-mode: on-change + * + * The proximity sensor which turns the screen off and back on during calls is the + * wake-up proximity sensor. Implement wake-up proximity sensor before implementing + * a non wake-up proximity sensor. For the wake-up proximity sensor set the flag + * SENSOR_FLAG_WAKE_UP. + * The value corresponds to the distance to the nearest object in centimeters. + */ + ASENSOR_TYPE_PROXIMITY = 8 +}; + +/** + * Sensor accuracy measure. + */ +enum { + /** no contact */ + ASENSOR_STATUS_NO_CONTACT = -1, + /** unreliable */ + ASENSOR_STATUS_UNRELIABLE = 0, + /** low accuracy */ + ASENSOR_STATUS_ACCURACY_LOW = 1, + /** medium accuracy */ + ASENSOR_STATUS_ACCURACY_MEDIUM = 2, + /** high accuracy */ + ASENSOR_STATUS_ACCURACY_HIGH = 3 +}; + +/** + * Sensor Reporting Modes. + */ +enum { + /** continuous reporting */ + AREPORTING_MODE_CONTINUOUS = 0, + /** reporting on change */ + AREPORTING_MODE_ON_CHANGE = 1, + /** on shot reporting */ + AREPORTING_MODE_ONE_SHOT = 2, + /** special trigger reporting */ + AREPORTING_MODE_SPECIAL_TRIGGER = 3 +}; + +/* + * A few useful constants + */ + +/** Earth's gravity in m/s^2 */ +#define ASENSOR_STANDARD_GRAVITY (9.80665f) +/** Maximum magnetic field on Earth's surface in uT */ +#define ASENSOR_MAGNETIC_FIELD_EARTH_MAX (60.0f) +/** Minimum magnetic field on Earth's surface in uT*/ +#define ASENSOR_MAGNETIC_FIELD_EARTH_MIN (30.0f) + +/** + * A sensor event. + */ + +/* NOTE: Must match hardware/sensors.h */ +typedef struct ASensorVector { + union { + float v[3]; + struct { + float x; + float y; + float z; + }; + struct { + float azimuth; + float pitch; + float roll; + }; + }; + int8_t status; + uint8_t reserved[3]; +} ASensorVector; + +typedef struct AMetaDataEvent { + int32_t what; + int32_t sensor; +} AMetaDataEvent; + +typedef struct AUncalibratedEvent { + union { + float uncalib[3]; + struct { + float x_uncalib; + float y_uncalib; + float z_uncalib; + }; + }; + union { + float bias[3]; + struct { + float x_bias; + float y_bias; + float z_bias; + }; + }; +} AUncalibratedEvent; + +typedef struct AHeartRateEvent { + float bpm; + int8_t status; +} AHeartRateEvent; + +/* NOTE: Must match hardware/sensors.h */ +typedef struct ASensorEvent { + int32_t version; /* sizeof(struct ASensorEvent) */ + int32_t sensor; + int32_t type; + int32_t reserved0; + int64_t timestamp; + union { + union { + float data[16]; + ASensorVector vector; + ASensorVector acceleration; + ASensorVector magnetic; + float temperature; + float distance; + float light; + float pressure; + float relative_humidity; + AUncalibratedEvent uncalibrated_gyro; + AUncalibratedEvent uncalibrated_magnetic; + AMetaDataEvent meta_data; + AHeartRateEvent heart_rate; + }; + union { + uint64_t data[8]; + uint64_t step_counter; + } u64; + }; + + uint32_t flags; + int32_t reserved1[3]; +} ASensorEvent; + +struct ASensorManager; +/** + * {@link ASensorManager} is an opaque type to manage sensors and + * events queues. + * + * {@link ASensorManager} is a singleton that can be obtained using + * ASensorManager_getInstance(). + * + * This file provides a set of functions that uses {@link + * ASensorManager} to access and list hardware sensors, and + * create and destroy event queues: + * - ASensorManager_getSensorList() + * - ASensorManager_getDefaultSensor() + * - ASensorManager_getDefaultSensorEx() + * - ASensorManager_createEventQueue() + * - ASensorManager_destroyEventQueue() + */ +typedef struct ASensorManager ASensorManager; + + +struct ASensorEventQueue; +/** + * {@link ASensorEventQueue} is an opaque type that provides access to + * {@link ASensorEvent} from hardware sensors. + * + * A new {@link ASensorEventQueue} can be obtained using ASensorManager_createEventQueue(). + * + * This file provides a set of functions to enable and disable + * sensors, check and get events, and set event rates on a {@link + * ASensorEventQueue}. + * - ASensorEventQueue_enableSensor() + * - ASensorEventQueue_disableSensor() + * - ASensorEventQueue_hasEvents() + * - ASensorEventQueue_getEvents() + * - ASensorEventQueue_setEventRate() + */ +typedef struct ASensorEventQueue ASensorEventQueue; + +struct ASensor; +/** + * {@link ASensor} is an opaque type that provides information about + * an hardware sensors. + * + * A {@link ASensor} pointer can be obtained using + * ASensorManager_getDefaultSensor(), + * ASensorManager_getDefaultSensorEx() or from a {@link ASensorList}. + * + * This file provides a set of functions to access properties of a + * {@link ASensor}: + * - ASensor_getName() + * - ASensor_getVendor() + * - ASensor_getType() + * - ASensor_getResolution() + * - ASensor_getMinDelay() + * - ASensor_getFifoMaxEventCount() + * - ASensor_getFifoReservedEventCount() + * - ASensor_getStringType() + * - ASensor_getReportingMode() + * - ASensor_isWakeUpSensor() + */ +typedef struct ASensor ASensor; +/** + * {@link ASensorRef} is a type for constant pointers to {@link ASensor}. + * + * This is used to define entry in {@link ASensorList} arrays. + */ +typedef ASensor const* ASensorRef; +/** + * {@link ASensorList} is an array of reference to {@link ASensor}. + * + * A {@link ASensorList} can be initialized using ASensorManager_getSensorList(). + */ +typedef ASensorRef const* ASensorList; + +/*****************************************************************************/ + +/** + * Get a reference to the sensor manager. ASensorManager is a singleton + * per package as different packages may have access to different sensors. + * + * Deprecated: Use ASensorManager_getInstanceForPackage(const char*) instead. + * + * Example: + * + * ASensorManager* sensorManager = ASensorManager_getInstance(); + * + */ +__attribute__ ((deprecated)) ASensorManager* ASensorManager_getInstance(); + +/* + * Get a reference to the sensor manager. ASensorManager is a singleton + * per package as different packages may have access to different sensors. + * + * Example: + * + * ASensorManager* sensorManager = ASensorManager_getInstanceForPackage("foo.bar.baz"); + * + */ +ASensorManager* ASensorManager_getInstanceForPackage(const char* packageName); + +/** + * Returns the list of available sensors. + */ +int ASensorManager_getSensorList(ASensorManager* manager, ASensorList* list); + +/** + * Returns the default sensor for the given type, or NULL if no sensor + * of that type exists. + */ +ASensor const* ASensorManager_getDefaultSensor(ASensorManager* manager, int type); + +/** + * Returns the default sensor with the given type and wakeUp properties or NULL if no sensor + * of this type and wakeUp properties exists. + */ +ASensor const* ASensorManager_getDefaultSensorEx(ASensorManager* manager, int type, + bool wakeUp); + +/** + * Creates a new sensor event queue and associate it with a looper. + * + * "ident" is a identifier for the events that will be returned when + * calling ALooper_pollOnce(). The identifier must be >= 0, or + * ALOOPER_POLL_CALLBACK if providing a non-NULL callback. + */ +ASensorEventQueue* ASensorManager_createEventQueue(ASensorManager* manager, + ALooper* looper, int ident, ALooper_callbackFunc callback, void* data); + +/** + * Destroys the event queue and free all resources associated to it. + */ +int ASensorManager_destroyEventQueue(ASensorManager* manager, ASensorEventQueue* queue); + + +/*****************************************************************************/ + +/** + * Enable the selected sensor. Returns a negative error code on failure. + */ +int ASensorEventQueue_enableSensor(ASensorEventQueue* queue, ASensor const* sensor); + +/** + * Disable the selected sensor. Returns a negative error code on failure. + */ +int ASensorEventQueue_disableSensor(ASensorEventQueue* queue, ASensor const* sensor); + +/** + * Sets the delivery rate of events in microseconds for the given sensor. + * Note that this is a hint only, generally event will arrive at a higher + * rate. It is an error to set a rate inferior to the value returned by + * ASensor_getMinDelay(). + * Returns a negative error code on failure. + */ +int ASensorEventQueue_setEventRate(ASensorEventQueue* queue, ASensor const* sensor, int32_t usec); + +/** + * Returns true if there are one or more events available in the + * sensor queue. Returns 1 if the queue has events; 0 if + * it does not have events; and a negative value if there is an error. + */ +int ASensorEventQueue_hasEvents(ASensorEventQueue* queue); + +/** + * Returns the next available events from the queue. Returns a negative + * value if no events are available or an error has occurred, otherwise + * the number of events returned. + * + * Examples: + * ASensorEvent event; + * ssize_t numEvent = ASensorEventQueue_getEvents(queue, &event, 1); + * + * ASensorEvent eventBuffer[8]; + * ssize_t numEvent = ASensorEventQueue_getEvents(queue, eventBuffer, 8); + * + */ +ssize_t ASensorEventQueue_getEvents(ASensorEventQueue* queue, + ASensorEvent* events, size_t count); + + +/*****************************************************************************/ + +/** + * Returns this sensor's name (non localized) + */ +const char* ASensor_getName(ASensor const* sensor); + +/** + * Returns this sensor's vendor's name (non localized) + */ +const char* ASensor_getVendor(ASensor const* sensor); + +/** + * Return this sensor's type + */ +int ASensor_getType(ASensor const* sensor); + +/** + * Returns this sensors's resolution + */ +float ASensor_getResolution(ASensor const* sensor); + +/** + * Returns the minimum delay allowed between events in microseconds. + * A value of zero means that this sensor doesn't report events at a + * constant rate, but rather only when a new data is available. + */ +int ASensor_getMinDelay(ASensor const* sensor); + +/** + * Returns the maximum size of batches for this sensor. Batches will often be + * smaller, as the hardware fifo might be used for other sensors. + */ +int ASensor_getFifoMaxEventCount(ASensor const* sensor); + +/** + * Returns the hardware batch fifo size reserved to this sensor. + */ +int ASensor_getFifoReservedEventCount(ASensor const* sensor); + +/** + * Returns this sensor's string type. + */ +const char* ASensor_getStringType(ASensor const* sensor); + +/** + * Returns the reporting mode for this sensor. One of AREPORTING_MODE_* constants. + */ +int ASensor_getReportingMode(ASensor const* sensor); + +/** + * Returns true if this is a wake up sensor, false otherwise. + */ +bool ASensor_isWakeUpSensor(ASensor const* sensor); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_SENSOR_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/storage_manager.h b/third_party/android_frameworks_native/include/android/storage_manager.h new file mode 100644 index 00000000000000..7f2ee08d62c347 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/storage_manager.h @@ -0,0 +1,154 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup Storage + * @{ + */ + +/** + * @file storage_manager.h + */ + +#ifndef ANDROID_STORAGE_MANAGER_H +#define ANDROID_STORAGE_MANAGER_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +struct AStorageManager; +/** + * {@link AStorageManager} manages application OBB storage, a pointer + * can be obtained with AStorageManager_new(). + */ +typedef struct AStorageManager AStorageManager; + +/** + * The different states of a OBB storage passed to AStorageManager_obbCallbackFunc(). + */ +enum { + /** + * The OBB container is now mounted and ready for use. Can be returned + * as the status for callbacks made during asynchronous OBB actions. + */ + AOBB_STATE_MOUNTED = 1, + + /** + * The OBB container is now unmounted and not usable. Can be returned + * as the status for callbacks made during asynchronous OBB actions. + */ + AOBB_STATE_UNMOUNTED = 2, + + /** + * There was an internal system error encountered while trying to + * mount the OBB. Can be returned as the status for callbacks made + * during asynchronous OBB actions. + */ + AOBB_STATE_ERROR_INTERNAL = 20, + + /** + * The OBB could not be mounted by the system. Can be returned as the + * status for callbacks made during asynchronous OBB actions. + */ + AOBB_STATE_ERROR_COULD_NOT_MOUNT = 21, + + /** + * The OBB could not be unmounted. This most likely indicates that a + * file is in use on the OBB. Can be returned as the status for + * callbacks made during asynchronous OBB actions. + */ + AOBB_STATE_ERROR_COULD_NOT_UNMOUNT = 22, + + /** + * A call was made to unmount the OBB when it was not mounted. Can be + * returned as the status for callbacks made during asynchronous OBB + * actions. + */ + AOBB_STATE_ERROR_NOT_MOUNTED = 23, + + /** + * The OBB has already been mounted. Can be returned as the status for + * callbacks made during asynchronous OBB actions. + */ + AOBB_STATE_ERROR_ALREADY_MOUNTED = 24, + + /** + * The current application does not have permission to use this OBB. + * This could be because the OBB indicates it's owned by a different + * package. Can be returned as the status for callbacks made during + * asynchronous OBB actions. + */ + AOBB_STATE_ERROR_PERMISSION_DENIED = 25, +}; + +/** + * Obtains a new instance of AStorageManager. + */ +AStorageManager* AStorageManager_new(); + +/** + * Release AStorageManager instance. + */ +void AStorageManager_delete(AStorageManager* mgr); + +/** + * Callback function for asynchronous calls made on OBB files. + * + * "state" is one of the following constants: + * - {@link AOBB_STATE_MOUNTED} + * - {@link AOBB_STATE_UNMOUNTED} + * - {@link AOBB_STATE_ERROR_INTERNAL} + * - {@link AOBB_STATE_ERROR_COULD_NOT_MOUNT} + * - {@link AOBB_STATE_ERROR_COULD_NOT_UNMOUNT} + * - {@link AOBB_STATE_ERROR_NOT_MOUNTED} + * - {@link AOBB_STATE_ERROR_ALREADY_MOUNTED} + * - {@link AOBB_STATE_ERROR_PERMISSION_DENIED} + */ +typedef void (*AStorageManager_obbCallbackFunc)(const char* filename, const int32_t state, void* data); + +/** + * Attempts to mount an OBB file. This is an asynchronous operation. + */ +void AStorageManager_mountObb(AStorageManager* mgr, const char* filename, const char* key, + AStorageManager_obbCallbackFunc cb, void* data); + +/** + * Attempts to unmount an OBB file. This is an asynchronous operation. + */ +void AStorageManager_unmountObb(AStorageManager* mgr, const char* filename, const int force, + AStorageManager_obbCallbackFunc cb, void* data); + +/** + * Check whether an OBB is mounted. + */ +int AStorageManager_isObbMounted(AStorageManager* mgr, const char* filename); + +/** + * Get the mounted path for an OBB. + */ +const char* AStorageManager_getMountedObbPath(AStorageManager* mgr, const char* filename); + + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_STORAGE_MANAGER_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/android/trace.h b/third_party/android_frameworks_native/include/android/trace.h new file mode 100644 index 00000000000000..e42e3341024dc4 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/trace.h @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_NATIVE_TRACE_H +#define ANDROID_NATIVE_TRACE_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Returns true if tracing is enabled. Use this signal to avoid expensive computation only necessary + * when tracing is enabled. + */ +bool ATrace_isEnabled(); + +/** + * Writes a tracing message to indicate that the given section of code has begun. This call must be + * followed by a corresponding call to endSection() on the same thread. + * + * Note: At this time the vertical bar character '|' and newline character '\n' are used internally + * by the tracing mechanism. If sectionName contains these characters they will be replaced with a + * space character in the trace. + */ +void ATrace_beginSection(const char* sectionName); + +/** + * Writes a tracing message to indicate that a given section of code has ended. This call must be + * preceeded by a corresponding call to beginSection(char*) on the same thread. Calling this method + * will mark the end of the most recently begun section of code, so care must be taken to ensure + * that beginSection / endSection pairs are properly nested and called from the same thread. + */ +void ATrace_endSection(); + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_NATIVE_TRACE_H diff --git a/third_party/android_frameworks_native/include/android/window.h b/third_party/android_frameworks_native/include/android/window.h new file mode 100644 index 00000000000000..436bf3a8307ce0 --- /dev/null +++ b/third_party/android_frameworks_native/include/android/window.h @@ -0,0 +1,224 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @addtogroup NativeActivity Native Activity + * @{ + */ + +/** + * @file window.h + */ + +#ifndef ANDROID_WINDOW_H +#define ANDROID_WINDOW_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Window flags, as per the Java API at android.view.WindowManager.LayoutParams. + */ +enum { + /** + * As long as this window is visible to the user, allow the lock + * screen to activate while the screen is on. This can be used + * independently, or in combination with {@link + * AWINDOW_FLAG_KEEP_SCREEN_ON} and/or {@link + * AWINDOW_FLAG_SHOW_WHEN_LOCKED} + */ + AWINDOW_FLAG_ALLOW_LOCK_WHILE_SCREEN_ON = 0x00000001, + /** Everything behind this window will be dimmed. */ + AWINDOW_FLAG_DIM_BEHIND = 0x00000002, + /** + * Blur everything behind this window. + * @deprecated Blurring is no longer supported. + */ + AWINDOW_FLAG_BLUR_BEHIND = 0x00000004, + /** + * This window won't ever get key input focus, so the + * user can not send key or other button events to it. Those will + * instead go to whatever focusable window is behind it. This flag + * will also enable {@link AWINDOW_FLAG_NOT_TOUCH_MODAL} whether or not that + * is explicitly set. + * + * Setting this flag also implies that the window will not need to + * interact with + * a soft input method, so it will be Z-ordered and positioned + * independently of any active input method (typically this means it + * gets Z-ordered on top of the input method, so it can use the full + * screen for its content and cover the input method if needed. You + * can use {@link AWINDOW_FLAG_ALT_FOCUSABLE_IM} to modify this behavior. + */ + AWINDOW_FLAG_NOT_FOCUSABLE = 0x00000008, + /** this window can never receive touch events. */ + AWINDOW_FLAG_NOT_TOUCHABLE = 0x00000010, + /** + * Even when this window is focusable (its + * {@link AWINDOW_FLAG_NOT_FOCUSABLE} is not set), allow any pointer events + * outside of the window to be sent to the windows behind it. Otherwise + * it will consume all pointer events itself, regardless of whether they + * are inside of the window. + */ + AWINDOW_FLAG_NOT_TOUCH_MODAL = 0x00000020, + /** + * When set, if the device is asleep when the touch + * screen is pressed, you will receive this first touch event. Usually + * the first touch event is consumed by the system since the user can + * not see what they are pressing on. + * + * @deprecated This flag has no effect. + */ + AWINDOW_FLAG_TOUCHABLE_WHEN_WAKING = 0x00000040, + /** + * As long as this window is visible to the user, keep + * the device's screen turned on and bright. + */ + AWINDOW_FLAG_KEEP_SCREEN_ON = 0x00000080, + /** + * Place the window within the entire screen, ignoring + * decorations around the border (such as the status bar). The + * window must correctly position its contents to take the screen + * decoration into account. + */ + AWINDOW_FLAG_LAYOUT_IN_SCREEN = 0x00000100, + /** allow window to extend outside of the screen. */ + AWINDOW_FLAG_LAYOUT_NO_LIMITS = 0x00000200, + /** + * Hide all screen decorations (such as the status + * bar) while this window is displayed. This allows the window to + * use the entire display space for itself -- the status bar will + * be hidden when an app window with this flag set is on the top + * layer. A fullscreen window will ignore a value of {@link + * AWINDOW_SOFT_INPUT_ADJUST_RESIZE}; the window will stay + * fullscreen and will not resize. + */ + AWINDOW_FLAG_FULLSCREEN = 0x00000400, + /** + * Override {@link AWINDOW_FLAG_FULLSCREEN} and force the + * screen decorations (such as the status bar) to be shown. + */ + AWINDOW_FLAG_FORCE_NOT_FULLSCREEN = 0x00000800, + /** + * Turn on dithering when compositing this window to + * the screen. + * @deprecated This flag is no longer used. + */ + AWINDOW_FLAG_DITHER = 0x00001000, + /** + * Treat the content of the window as secure, preventing + * it from appearing in screenshots or from being viewed on non-secure + * displays. + */ + AWINDOW_FLAG_SECURE = 0x00002000, + /** + * A special mode where the layout parameters are used + * to perform scaling of the surface when it is composited to the + * screen. + */ + AWINDOW_FLAG_SCALED = 0x00004000, + /** + * Intended for windows that will often be used when the user is + * holding the screen against their face, it will aggressively + * filter the event stream to prevent unintended presses in this + * situation that may not be desired for a particular window, when + * such an event stream is detected, the application will receive + * a {@link AMOTION_EVENT_ACTION_CANCEL} to indicate this so + * applications can handle this accordingly by taking no action on + * the event until the finger is released. + */ + AWINDOW_FLAG_IGNORE_CHEEK_PRESSES = 0x00008000, + /** + * A special option only for use in combination with + * {@link AWINDOW_FLAG_LAYOUT_IN_SCREEN}. When requesting layout in the + * screen your window may appear on top of or behind screen decorations + * such as the status bar. By also including this flag, the window + * manager will report the inset rectangle needed to ensure your + * content is not covered by screen decorations. + */ + AWINDOW_FLAG_LAYOUT_INSET_DECOR = 0x00010000, + /** + * Invert the state of {@link AWINDOW_FLAG_NOT_FOCUSABLE} with + * respect to how this window interacts with the current method. + * That is, if FLAG_NOT_FOCUSABLE is set and this flag is set, + * then the window will behave as if it needs to interact with the + * input method and thus be placed behind/away from it; if {@link + * AWINDOW_FLAG_NOT_FOCUSABLE} is not set and this flag is set, + * then the window will behave as if it doesn't need to interact + * with the input method and can be placed to use more space and + * cover the input method. + */ + AWINDOW_FLAG_ALT_FOCUSABLE_IM = 0x00020000, + /** + * If you have set {@link AWINDOW_FLAG_NOT_TOUCH_MODAL}, you + * can set this flag to receive a single special MotionEvent with + * the action + * {@link AMOTION_EVENT_ACTION_OUTSIDE} for + * touches that occur outside of your window. Note that you will not + * receive the full down/move/up gesture, only the location of the + * first down as an {@link AMOTION_EVENT_ACTION_OUTSIDE}. + */ + AWINDOW_FLAG_WATCH_OUTSIDE_TOUCH = 0x00040000, + /** + * Special flag to let windows be shown when the screen + * is locked. This will let application windows take precedence over + * key guard or any other lock screens. Can be used with + * {@link AWINDOW_FLAG_KEEP_SCREEN_ON} to turn screen on and display windows + * directly before showing the key guard window. Can be used with + * {@link AWINDOW_FLAG_DISMISS_KEYGUARD} to automatically fully dismisss + * non-secure keyguards. This flag only applies to the top-most + * full-screen window. + */ + AWINDOW_FLAG_SHOW_WHEN_LOCKED = 0x00080000, + /** + * Ask that the system wallpaper be shown behind + * your window. The window surface must be translucent to be able + * to actually see the wallpaper behind it; this flag just ensures + * that the wallpaper surface will be there if this window actually + * has translucent regions. + */ + AWINDOW_FLAG_SHOW_WALLPAPER = 0x00100000, + /** + * When set as a window is being added or made + * visible, once the window has been shown then the system will + * poke the power manager's user activity (as if the user had woken + * up the device) to turn the screen on. + */ + AWINDOW_FLAG_TURN_SCREEN_ON = 0x00200000, + /** + * When set the window will cause the keyguard to + * be dismissed, only if it is not a secure lock keyguard. Because such + * a keyguard is not needed for security, it will never re-appear if + * the user navigates to another window (in contrast to + * {@link AWINDOW_FLAG_SHOW_WHEN_LOCKED}, which will only temporarily + * hide both secure and non-secure keyguards but ensure they reappear + * when the user moves to another UI that doesn't hide them). + * If the keyguard is currently active and is secure (requires an + * unlock pattern) than the user will still need to confirm it before + * seeing this window, unless {@link AWINDOW_FLAG_SHOW_WHEN_LOCKED} has + * also been set. + */ + AWINDOW_FLAG_DISMISS_KEYGUARD = 0x00400000, +}; + +#ifdef __cplusplus +}; +#endif + +#endif // ANDROID_WINDOW_H + +/** @} */ diff --git a/third_party/android_frameworks_native/include/binder/AppOpsManager.h b/third_party/android_frameworks_native/include/binder/AppOpsManager.h new file mode 100644 index 00000000000000..1d0e968c4a43fb --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/AppOpsManager.h @@ -0,0 +1,130 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_APP_OPS_MANAGER_H +#define ANDROID_APP_OPS_MANAGER_H + +#include + +#include + +// --------------------------------------------------------------------------- +namespace android { + +class AppOpsManager +{ +public: + enum { + MODE_ALLOWED = IAppOpsService::MODE_ALLOWED, + MODE_IGNORED = IAppOpsService::MODE_IGNORED, + MODE_ERRORED = IAppOpsService::MODE_ERRORED + }; + + enum { + OP_NONE = -1, + OP_COARSE_LOCATION = 0, + OP_FINE_LOCATION = 1, + OP_GPS = 2, + OP_VIBRATE = 3, + OP_READ_CONTACTS = 4, + OP_WRITE_CONTACTS = 5, + OP_READ_CALL_LOG = 6, + OP_WRITE_CALL_LOG = 7, + OP_READ_CALENDAR = 8, + OP_WRITE_CALENDAR = 9, + OP_WIFI_SCAN = 10, + OP_POST_NOTIFICATION = 11, + OP_NEIGHBORING_CELLS = 12, + OP_CALL_PHONE = 13, + OP_READ_SMS = 14, + OP_WRITE_SMS = 15, + OP_RECEIVE_SMS = 16, + OP_RECEIVE_EMERGECY_SMS = 17, + OP_RECEIVE_MMS = 18, + OP_RECEIVE_WAP_PUSH = 19, + OP_SEND_SMS = 20, + OP_READ_ICC_SMS = 21, + OP_WRITE_ICC_SMS = 22, + OP_WRITE_SETTINGS = 23, + OP_SYSTEM_ALERT_WINDOW = 24, + OP_ACCESS_NOTIFICATIONS = 25, + OP_CAMERA = 26, + OP_RECORD_AUDIO = 27, + OP_PLAY_AUDIO = 28, + OP_READ_CLIPBOARD = 29, + OP_WRITE_CLIPBOARD = 30, + OP_TAKE_MEDIA_BUTTONS = 31, + OP_TAKE_AUDIO_FOCUS = 32, + OP_AUDIO_MASTER_VOLUME = 33, + OP_AUDIO_VOICE_VOLUME = 34, + OP_AUDIO_RING_VOLUME = 35, + OP_AUDIO_MEDIA_VOLUME = 36, + OP_AUDIO_ALARM_VOLUME = 37, + OP_AUDIO_NOTIFICATION_VOLUME = 38, + OP_AUDIO_BLUETOOTH_VOLUME = 39, + OP_WAKE_LOCK = 40, + OP_MONITOR_LOCATION = 41, + OP_MONITOR_HIGH_POWER_LOCATION = 42, + OP_GET_USAGE_STATS = 43, + OP_MUTE_MICROPHONE = 44, + OP_TOAST_WINDOW = 45, + OP_PROJECT_MEDIA = 46, + OP_ACTIVATE_VPN = 47, + OP_WRITE_WALLPAPER = 48, + OP_ASSIST_STRUCTURE = 49, + OP_ASSIST_SCREENSHOT = 50, + OP_READ_PHONE_STATE = 51, + OP_ADD_VOICEMAIL = 52, + OP_USE_SIP = 53, + OP_PROCESS_OUTGOING_CALLS = 54, + OP_USE_FINGERPRINT = 55, + OP_BODY_SENSORS = 56, + OP_READ_CELL_BROADCASTS = 57, + OP_MOCK_LOCATION = 58, + OP_READ_EXTERNAL_STORAGE = 59, + OP_WRITE_EXTERNAL_STORAGE = 60, + OP_TURN_SCREEN_ON = 61, + OP_GET_ACCOUNTS = 62, + OP_WIFI_CHANGE = 63, + OP_BLUETOOTH_CHANGE = 64, + OP_BOOT_COMPLETED = 65, + OP_NFC_CHANGE = 66, + OP_DATA_CONNECT_CHANGE = 67, + OP_SU = 68 + }; + + AppOpsManager(); + + int32_t checkOp(int32_t op, int32_t uid, const String16& callingPackage); + int32_t noteOp(int32_t op, int32_t uid, const String16& callingPackage); + int32_t startOp(int32_t op, int32_t uid, const String16& callingPackage); + void finishOp(int32_t op, int32_t uid, const String16& callingPackage); + void startWatchingMode(int32_t op, const String16& packageName, + const sp& callback); + void stopWatchingMode(const sp& callback); + int32_t permissionToOpCode(const String16& permission); + +private: + Mutex mLock; + sp mService; + + sp getService(); +}; + + +}; // namespace android +// --------------------------------------------------------------------------- +#endif // ANDROID_APP_OPS_MANAGER_H diff --git a/third_party/android_frameworks_native/include/binder/Binder.h b/third_party/android_frameworks_native/include/binder/Binder.h new file mode 100644 index 00000000000000..86628a03d351e6 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/Binder.h @@ -0,0 +1,105 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BINDER_H +#define ANDROID_BINDER_H + +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +class BBinder : public IBinder +{ +public: + BBinder(); + + virtual const String16& getInterfaceDescriptor() const; + virtual bool isBinderAlive() const; + virtual status_t pingBinder(); + virtual status_t dump(int fd, const Vector& args); + + virtual status_t transact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); + + virtual status_t linkToDeath(const sp& recipient, + void* cookie = NULL, + uint32_t flags = 0); + + virtual status_t unlinkToDeath( const wp& recipient, + void* cookie = NULL, + uint32_t flags = 0, + wp* outRecipient = NULL); + + virtual void attachObject( const void* objectID, + void* object, + void* cleanupCookie, + object_cleanup_func func); + virtual void* findObject(const void* objectID) const; + virtual void detachObject(const void* objectID); + + virtual BBinder* localBinder(); + +protected: + virtual ~BBinder(); + + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); + +private: + BBinder(const BBinder& o); + BBinder& operator=(const BBinder& o); + + class Extras; + + atomic_uintptr_t mExtras; // should be atomic + void* mReserved0; +}; + +// --------------------------------------------------------------------------- + +class BpRefBase : public virtual RefBase +{ +protected: + BpRefBase(const sp& o); + virtual ~BpRefBase(); + virtual void onFirstRef(); + virtual void onLastStrongRef(const void* id); + virtual bool onIncStrongAttempted(uint32_t flags, const void* id); + + inline IBinder* remote() { return mRemote; } + inline IBinder* remote() const { return mRemote; } + +private: + BpRefBase(const BpRefBase& o); + BpRefBase& operator=(const BpRefBase& o); + + IBinder* const mRemote; + RefBase::weakref_type* mRefs; + volatile int32_t mState; +}; + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_BINDER_H diff --git a/third_party/android_frameworks_native/include/binder/BinderService.h b/third_party/android_frameworks_native/include/binder/BinderService.h new file mode 100644 index 00000000000000..ef703bda904b9e --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/BinderService.h @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BINDER_SERVICE_H +#define ANDROID_BINDER_SERVICE_H + +#include + +#include +#include + +#include +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +template +class BinderService +{ +public: + static status_t publish(bool allowIsolated = false) { + sp sm(defaultServiceManager()); + return sm->addService( + String16(SERVICE::getServiceName()), + new SERVICE(), allowIsolated); + } + + static void publishAndJoinThreadPool(bool allowIsolated = false) { + publish(allowIsolated); + joinThreadPool(); + } + + static void instantiate() { publish(); } + + static status_t shutdown() { return NO_ERROR; } + +private: + static void joinThreadPool() { + sp ps(ProcessState::self()); + ps->startThreadPool(); + ps->giveThreadPoolName(); + IPCThreadState::self()->joinThreadPool(); + } +}; + + +}; // namespace android +// --------------------------------------------------------------------------- +#endif // ANDROID_BINDER_SERVICE_H diff --git a/third_party/android_frameworks_native/include/binder/BpBinder.h b/third_party/android_frameworks_native/include/binder/BpBinder.h new file mode 100644 index 00000000000000..7ef93aa390414f --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/BpBinder.h @@ -0,0 +1,124 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BPBINDER_H +#define ANDROID_BPBINDER_H + +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +class BpBinder : public IBinder +{ +public: + BpBinder(int32_t handle); + + inline int32_t handle() const { return mHandle; } + + virtual const String16& getInterfaceDescriptor() const; + virtual bool isBinderAlive() const; + virtual status_t pingBinder(); + virtual status_t dump(int fd, const Vector& args); + + virtual status_t transact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); + + virtual status_t linkToDeath(const sp& recipient, + void* cookie = NULL, + uint32_t flags = 0); + virtual status_t unlinkToDeath( const wp& recipient, + void* cookie = NULL, + uint32_t flags = 0, + wp* outRecipient = NULL); + + virtual void attachObject( const void* objectID, + void* object, + void* cleanupCookie, + object_cleanup_func func); + virtual void* findObject(const void* objectID) const; + virtual void detachObject(const void* objectID); + + virtual BpBinder* remoteBinder(); + + status_t setConstantData(const void* data, size_t size); + void sendObituary(); + + class ObjectManager + { + public: + ObjectManager(); + ~ObjectManager(); + + void attach( const void* objectID, + void* object, + void* cleanupCookie, + IBinder::object_cleanup_func func); + void* find(const void* objectID) const; + void detach(const void* objectID); + + void kill(); + + private: + ObjectManager(const ObjectManager&); + ObjectManager& operator=(const ObjectManager&); + + struct entry_t + { + void* object; + void* cleanupCookie; + IBinder::object_cleanup_func func; + }; + + KeyedVector mObjects; + }; + +protected: + virtual ~BpBinder(); + virtual void onFirstRef(); + virtual void onLastStrongRef(const void* id); + virtual bool onIncStrongAttempted(uint32_t flags, const void* id); + +private: + const int32_t mHandle; + + struct Obituary { + wp recipient; + void* cookie; + uint32_t flags; + }; + + void reportOneDeath(const Obituary& obit); + bool isDescriptorCached() const; + + mutable Mutex mLock; + volatile int32_t mAlive; + volatile int32_t mObitsSent; + Vector* mObituaries; + ObjectManager mObjects; + Parcel* mConstantData; + mutable String16 mDescriptorCache; +}; + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_BPBINDER_H diff --git a/third_party/android_frameworks_native/include/binder/BufferedTextOutput.h b/third_party/android_frameworks_native/include/binder/BufferedTextOutput.h new file mode 100644 index 00000000000000..9a7c43bb13996d --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/BufferedTextOutput.h @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BUFFEREDTEXTOUTPUT_H +#define ANDROID_BUFFEREDTEXTOUTPUT_H + +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +class BufferedTextOutput : public TextOutput +{ +public: + //** Flags for constructor */ + enum { + MULTITHREADED = 0x0001 + }; + + BufferedTextOutput(uint32_t flags = 0); + virtual ~BufferedTextOutput(); + + virtual status_t print(const char* txt, size_t len); + virtual void moveIndent(int delta); + + virtual void pushBundle(); + virtual void popBundle(); + +protected: + virtual status_t writeLines(const struct iovec& vec, size_t N) = 0; + +private: + struct BufferState; + struct ThreadState; + + static ThreadState*getThreadState(); + static void threadDestructor(void *st); + + BufferState*getBuffer() const; + + uint32_t mFlags; + const int32_t mSeq; + const int32_t mIndex; + + Mutex mLock; + BufferState* mGlobalState; +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_BUFFEREDTEXTOUTPUT_H diff --git a/third_party/android_frameworks_native/include/binder/Debug.h b/third_party/android_frameworks_native/include/binder/Debug.h new file mode 100644 index 00000000000000..f6a335502fe2cc --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/Debug.h @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BINDER_DEBUG_H +#define ANDROID_BINDER_DEBUG_H + +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +const char* stringForIndent(int32_t indentLevel); + +typedef void (*debugPrintFunc)(void* cookie, const char* txt); + +void printTypeCode(uint32_t typeCode, + debugPrintFunc func = 0, void* cookie = 0); + +void printHexData(int32_t indent, const void *buf, size_t length, + size_t bytesPerLine=16, int32_t singleLineBytesCutoff=16, + size_t alignment=0, bool cArrayStyle=false, + debugPrintFunc func = 0, void* cookie = 0); + +#ifdef __cplusplus +} +#endif + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_BINDER_DEBUG_H diff --git a/third_party/android_frameworks_native/include/binder/IAppOpsCallback.h b/third_party/android_frameworks_native/include/binder/IAppOpsCallback.h new file mode 100644 index 00000000000000..7f8eb0168b7224 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IAppOpsCallback.h @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +#ifndef ANDROID_IAPP_OPS_CALLBACK_H +#define ANDROID_IAPP_OPS_CALLBACK_H + +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IAppOpsCallback : public IInterface +{ +public: + DECLARE_META_INTERFACE(AppOpsCallback); + + virtual void opChanged(int32_t op, const String16& packageName) = 0; + + enum { + OP_CHANGED_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION + }; +}; + +// ---------------------------------------------------------------------- + +class BnAppOpsCallback : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IAPP_OPS_CALLBACK_H + diff --git a/third_party/android_frameworks_native/include/binder/IAppOpsService.h b/third_party/android_frameworks_native/include/binder/IAppOpsService.h new file mode 100644 index 00000000000000..cd81efa363fe45 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IAppOpsService.h @@ -0,0 +1,78 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +#ifndef ANDROID_IAPP_OPS_SERVICE_H +#define ANDROID_IAPP_OPS_SERVICE_H + +#include +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IAppOpsService : public IInterface +{ +public: + DECLARE_META_INTERFACE(AppOpsService); + + virtual int32_t checkOperation(int32_t code, int32_t uid, const String16& packageName) = 0; + virtual int32_t noteOperation(int32_t code, int32_t uid, const String16& packageName) = 0; + virtual int32_t startOperation(const sp& token, int32_t code, int32_t uid, + const String16& packageName) = 0; + virtual void finishOperation(const sp& token, int32_t code, int32_t uid, + const String16& packageName) = 0; + virtual void startWatchingMode(int32_t op, const String16& packageName, + const sp& callback) = 0; + virtual void stopWatchingMode(const sp& callback) = 0; + virtual sp getToken(const sp& clientToken) = 0; + virtual int32_t permissionToOpCode(const String16& permission) = 0; + + enum { + CHECK_OPERATION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION, + NOTE_OPERATION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+1, + START_OPERATION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+2, + FINISH_OPERATION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+3, + START_WATCHING_MODE_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+4, + STOP_WATCHING_MODE_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+5, + GET_TOKEN_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+6, + PERMISSION_TO_OP_CODE_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION+7, + }; + + enum { + MODE_ALLOWED = 0, + MODE_IGNORED = 1, + MODE_ERRORED = 2 + }; +}; + +// ---------------------------------------------------------------------- + +class BnAppOpsService : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IAPP_OPS_SERVICE_H diff --git a/third_party/android_frameworks_native/include/binder/IBatteryStats.h b/third_party/android_frameworks_native/include/binder/IBatteryStats.h new file mode 100644 index 00000000000000..5f3818652be2dc --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IBatteryStats.h @@ -0,0 +1,79 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_IBATTERYSTATS_H +#define ANDROID_IBATTERYSTATS_H + +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IBatteryStats : public IInterface +{ +public: + DECLARE_META_INTERFACE(BatteryStats); + + virtual void noteStartSensor(int uid, int sensor) = 0; + virtual void noteStopSensor(int uid, int sensor) = 0; + virtual void noteStartVideo(int uid) = 0; + virtual void noteStopVideo(int uid) = 0; + virtual void noteStartAudio(int uid) = 0; + virtual void noteStopAudio(int uid) = 0; + virtual void noteResetVideo() = 0; + virtual void noteResetAudio() = 0; + virtual void noteFlashlightOn(int uid) = 0; + virtual void noteFlashlightOff(int uid) = 0; + virtual void noteStartCamera(int uid) = 0; + virtual void noteStopCamera(int uid) = 0; + virtual void noteResetCamera() = 0; + virtual void noteResetFlashlight() = 0; + + enum { + NOTE_START_SENSOR_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION, + NOTE_STOP_SENSOR_TRANSACTION, + NOTE_START_VIDEO_TRANSACTION, + NOTE_STOP_VIDEO_TRANSACTION, + NOTE_START_AUDIO_TRANSACTION, + NOTE_STOP_AUDIO_TRANSACTION, + NOTE_RESET_VIDEO_TRANSACTION, + NOTE_RESET_AUDIO_TRANSACTION, + NOTE_FLASHLIGHT_ON_TRANSACTION, + NOTE_FLASHLIGHT_OFF_TRANSACTION, + NOTE_START_CAMERA_TRANSACTION, + NOTE_STOP_CAMERA_TRANSACTION, + NOTE_RESET_CAMERA_TRANSACTION, + NOTE_RESET_FLASHLIGHT_TRANSACTION + }; +}; + +// ---------------------------------------------------------------------- + +class BnBatteryStats : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IBATTERYSTATS_H diff --git a/third_party/android_frameworks_native/include/binder/IBinder.h b/third_party/android_frameworks_native/include/binder/IBinder.h new file mode 100644 index 00000000000000..43b654334b027b --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IBinder.h @@ -0,0 +1,152 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_IBINDER_H +#define ANDROID_IBINDER_H + +#include +#include +#include +#include + + +#define B_PACK_CHARS(c1, c2, c3, c4) \ + ((((c1)<<24)) | (((c2)<<16)) | (((c3)<<8)) | (c4)) + +// --------------------------------------------------------------------------- +namespace android { + +class BBinder; +class BpBinder; +class IInterface; +class Parcel; + +/** + * Base class and low-level protocol for a remotable object. + * You can derive from this class to create an object for which other + * processes can hold references to it. Communication between processes + * (method calls, property get and set) is down through a low-level + * protocol implemented on top of the transact() API. + */ +class IBinder : public virtual RefBase +{ +public: + enum { + FIRST_CALL_TRANSACTION = 0x00000001, + LAST_CALL_TRANSACTION = 0x00ffffff, + + PING_TRANSACTION = B_PACK_CHARS('_','P','N','G'), + DUMP_TRANSACTION = B_PACK_CHARS('_','D','M','P'), + INTERFACE_TRANSACTION = B_PACK_CHARS('_', 'N', 'T', 'F'), + SYSPROPS_TRANSACTION = B_PACK_CHARS('_', 'S', 'P', 'R'), + + // Corresponds to TF_ONE_WAY -- an asynchronous call. + FLAG_ONEWAY = 0x00000001 + }; + + IBinder(); + + /** + * Check if this IBinder implements the interface named by + * @a descriptor. If it does, the base pointer to it is returned, + * which you can safely static_cast<> to the concrete C++ interface. + */ + virtual sp queryLocalInterface(const String16& descriptor); + + /** + * Return the canonical name of the interface provided by this IBinder + * object. + */ + virtual const String16& getInterfaceDescriptor() const = 0; + + virtual bool isBinderAlive() const = 0; + virtual status_t pingBinder() = 0; + virtual status_t dump(int fd, const Vector& args) = 0; + + virtual status_t transact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0) = 0; + + class DeathRecipient : public virtual RefBase + { + public: + virtual void binderDied(const wp& who) = 0; + }; + + /** + * Register the @a recipient for a notification if this binder + * goes away. If this binder object unexpectedly goes away + * (typically because its hosting process has been killed), + * then DeathRecipient::binderDied() will be called with a reference + * to this. + * + * The @a cookie is optional -- if non-NULL, it should be a + * memory address that you own (that is, you know it is unique). + * + * @note You will only receive death notifications for remote binders, + * as local binders by definition can't die without you dying as well. + * Trying to use this function on a local binder will result in an + * INVALID_OPERATION code being returned and nothing happening. + * + * @note This link always holds a weak reference to its recipient. + * + * @note You will only receive a weak reference to the dead + * binder. You should not try to promote this to a strong reference. + * (Nor should you need to, as there is nothing useful you can + * directly do with it now that it has passed on.) + */ + virtual status_t linkToDeath(const sp& recipient, + void* cookie = NULL, + uint32_t flags = 0) = 0; + + /** + * Remove a previously registered death notification. + * The @a recipient will no longer be called if this object + * dies. The @a cookie is optional. If non-NULL, you can + * supply a NULL @a recipient, and the recipient previously + * added with that cookie will be unlinked. + */ + virtual status_t unlinkToDeath( const wp& recipient, + void* cookie = NULL, + uint32_t flags = 0, + wp* outRecipient = NULL) = 0; + + virtual bool checkSubclass(const void* subclassID) const; + + typedef void (*object_cleanup_func)(const void* id, void* obj, void* cleanupCookie); + + virtual void attachObject( const void* objectID, + void* object, + void* cleanupCookie, + object_cleanup_func func) = 0; + virtual void* findObject(const void* objectID) const = 0; + virtual void detachObject(const void* objectID) = 0; + + virtual BBinder* localBinder(); + virtual BpBinder* remoteBinder(); + +protected: + virtual ~IBinder(); + +private: +}; + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_IBINDER_H diff --git a/third_party/android_frameworks_native/include/binder/IInterface.h b/third_party/android_frameworks_native/include/binder/IInterface.h new file mode 100644 index 00000000000000..4ce361380db7a2 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IInterface.h @@ -0,0 +1,150 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +#ifndef ANDROID_IINTERFACE_H +#define ANDROID_IINTERFACE_H + +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IInterface : public virtual RefBase +{ +public: + IInterface(); + static sp asBinder(const IInterface*); + static sp asBinder(const sp&); + +protected: + virtual ~IInterface(); + virtual IBinder* onAsBinder() = 0; +}; + +// ---------------------------------------------------------------------- + +template +inline sp interface_cast(const sp& obj) +{ + return INTERFACE::asInterface(obj); +} + +// ---------------------------------------------------------------------- + +template +class BnInterface : public INTERFACE, public BBinder +{ +public: + virtual sp queryLocalInterface(const String16& _descriptor); + virtual const String16& getInterfaceDescriptor() const; + +protected: + virtual IBinder* onAsBinder(); +}; + +// ---------------------------------------------------------------------- + +template +class BpInterface : public INTERFACE, public BpRefBase +{ +public: + BpInterface(const sp& remote); + +protected: + virtual IBinder* onAsBinder(); +}; + +// ---------------------------------------------------------------------- + +#define DECLARE_META_INTERFACE(INTERFACE) \ + static const android::String16 descriptor; \ + static android::sp asInterface( \ + const android::sp& obj); \ + virtual const android::String16& getInterfaceDescriptor() const; \ + I##INTERFACE(); \ + virtual ~I##INTERFACE(); \ + + +#define IMPLEMENT_META_INTERFACE(INTERFACE, NAME) \ + const android::String16 I##INTERFACE::descriptor(NAME); \ + const android::String16& \ + I##INTERFACE::getInterfaceDescriptor() const { \ + return I##INTERFACE::descriptor; \ + } \ + android::sp I##INTERFACE::asInterface( \ + const android::sp& obj) \ + { \ + android::sp intr; \ + if (obj != NULL) { \ + intr = static_cast( \ + obj->queryLocalInterface( \ + I##INTERFACE::descriptor).get()); \ + if (intr == NULL) { \ + intr = new Bp##INTERFACE(obj); \ + } \ + } \ + return intr; \ + } \ + I##INTERFACE::I##INTERFACE() { } \ + I##INTERFACE::~I##INTERFACE() { } \ + + +#define CHECK_INTERFACE(interface, data, reply) \ + if (!data.checkInterface(this)) { return PERMISSION_DENIED; } \ + + +// ---------------------------------------------------------------------- +// No user-serviceable parts after this... + +template +inline sp BnInterface::queryLocalInterface( + const String16& _descriptor) +{ + if (_descriptor == INTERFACE::descriptor) return this; + return NULL; +} + +template +inline const String16& BnInterface::getInterfaceDescriptor() const +{ + return INTERFACE::getInterfaceDescriptor(); +} + +template +IBinder* BnInterface::onAsBinder() +{ + return this; +} + +template +inline BpInterface::BpInterface(const sp& remote) + : BpRefBase(remote) +{ +} + +template +inline IBinder* BpInterface::onAsBinder() +{ + return remote(); +} + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IINTERFACE_H diff --git a/third_party/android_frameworks_native/include/binder/IMemory.h b/third_party/android_frameworks_native/include/binder/IMemory.h new file mode 100644 index 00000000000000..178ef85937301d --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IMemory.h @@ -0,0 +1,107 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_IMEMORY_H +#define ANDROID_IMEMORY_H + +#include +#include +#include + +#include +#include +#include + +namespace android { + +// ---------------------------------------------------------------------------- + +class IMemoryHeap : public IInterface +{ +public: + DECLARE_META_INTERFACE(MemoryHeap); + + // flags returned by getFlags() + enum { + READ_ONLY = 0x00000001, +#ifdef USE_MEMORY_HEAP_ION + USE_ION_FD = 0x00008000 +#else + USE_ION_FD = 0x00000008 +#endif + }; + + virtual int getHeapID() const = 0; + virtual void* getBase() const = 0; + virtual size_t getSize() const = 0; + virtual uint32_t getFlags() const = 0; + virtual uint32_t getOffset() const = 0; + + // these are there just for backward source compatibility + int32_t heapID() const { return getHeapID(); } + void* base() const { return getBase(); } + size_t virtualSize() const { return getSize(); } +}; + +class BnMemoryHeap : public BnInterface +{ +public: + virtual status_t onTransact( + uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); + + BnMemoryHeap(); +protected: + virtual ~BnMemoryHeap(); +}; + +// ---------------------------------------------------------------------------- + +class IMemory : public IInterface +{ +public: + DECLARE_META_INTERFACE(Memory); + + virtual sp getMemory(ssize_t* offset=0, size_t* size=0) const = 0; + + // helpers + void* fastPointer(const sp& heap, ssize_t offset) const; + void* pointer() const; + size_t size() const; + ssize_t offset() const; +}; + +class BnMemory : public BnInterface +{ +public: + virtual status_t onTransact( + uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); + + BnMemory(); +protected: + virtual ~BnMemory(); +}; + +// ---------------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IMEMORY_H diff --git a/third_party/android_frameworks_native/include/binder/IPCThreadState.h b/third_party/android_frameworks_native/include/binder/IPCThreadState.h new file mode 100644 index 00000000000000..1853cff235cec7 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IPCThreadState.h @@ -0,0 +1,135 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_IPC_THREAD_STATE_H +#define ANDROID_IPC_THREAD_STATE_H + +#include +#include +#include +#include + +#if defined(_WIN32) +typedef int uid_t; +#endif + +// --------------------------------------------------------------------------- +namespace android { + +class IPCThreadState +{ +public: + static IPCThreadState* self(); + static IPCThreadState* selfOrNull(); // self(), but won't instantiate + + sp process(); + + status_t clearLastError(); + + pid_t getCallingPid() const; + uid_t getCallingUid() const; + + void setStrictModePolicy(int32_t policy); + int32_t getStrictModePolicy() const; + + void setLastTransactionBinderFlags(int32_t flags); + int32_t getLastTransactionBinderFlags() const; + + int64_t clearCallingIdentity(); + void restoreCallingIdentity(int64_t token); + + int setupPolling(int* fd); + status_t handlePolledCommands(); + void flushCommands(); + + void joinThreadPool(bool isMain = true); + + // Stop the local process. + void stopProcess(bool immediate = true); + + status_t transact(int32_t handle, + uint32_t code, const Parcel& data, + Parcel* reply, uint32_t flags); + + void incStrongHandle(int32_t handle); + void decStrongHandle(int32_t handle); + void incWeakHandle(int32_t handle); + void decWeakHandle(int32_t handle); + status_t attemptIncStrongHandle(int32_t handle); + static void expungeHandle(int32_t handle, IBinder* binder); + status_t requestDeathNotification( int32_t handle, + BpBinder* proxy); + status_t clearDeathNotification( int32_t handle, + BpBinder* proxy); + + static void shutdown(); + + // Call this to disable switching threads to background scheduling when + // receiving incoming IPC calls. This is specifically here for the + // Android system process, since it expects to have background apps calling + // in to it but doesn't want to acquire locks in its services while in + // the background. + static void disableBackgroundScheduling(bool disable); + + // Call blocks until the number of executing binder threads is less than + // the maximum number of binder threads threads allowed for this process. + void blockUntilThreadAvailable(); + +private: + IPCThreadState(); + ~IPCThreadState(); + + status_t sendReply(const Parcel& reply, uint32_t flags); + status_t waitForResponse(Parcel *reply, + status_t *acquireResult=NULL); + status_t talkWithDriver(bool doReceive=true); + status_t writeTransactionData(int32_t cmd, + uint32_t binderFlags, + int32_t handle, + uint32_t code, + const Parcel& data, + status_t* statusBuffer); + status_t getAndExecuteCommand(); + status_t executeCommand(int32_t command); + void processPendingDerefs(); + + void clearCaller(); + + static void threadDestructor(void *st); + static void freeBuffer(Parcel* parcel, + const uint8_t* data, size_t dataSize, + const binder_size_t* objects, size_t objectsSize, + void* cookie); + + const sp mProcess; + const pid_t mMyThreadId; + Vector mPendingStrongDerefs; + Vector mPendingWeakDerefs; + + Parcel mIn; + Parcel mOut; + status_t mLastError; + pid_t mCallingPid; + uid_t mCallingUid; + int32_t mStrictModePolicy; + int32_t mLastTransactionBinderFlags; +}; + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_IPC_THREAD_STATE_H diff --git a/third_party/android_frameworks_native/include/binder/IPermissionController.h b/third_party/android_frameworks_native/include/binder/IPermissionController.h new file mode 100644 index 00000000000000..4e5fb34838c453 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IPermissionController.h @@ -0,0 +1,62 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +#ifndef ANDROID_IPERMISSION_CONTROLLER_H +#define ANDROID_IPERMISSION_CONTROLLER_H + +#include +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IPermissionController : public IInterface +{ +public: + DECLARE_META_INTERFACE(PermissionController); + + virtual bool checkPermission(const String16& permission, int32_t pid, int32_t uid) = 0; + + virtual void getPackagesForUid(const uid_t uid, Vector &packages) = 0; + + virtual bool isRuntimePermission(const String16& permission) = 0; + + enum { + CHECK_PERMISSION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION, + GET_PACKAGES_FOR_UID_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION + 1, + IS_RUNTIME_PERMISSION_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION + 2 + }; +}; + +// ---------------------------------------------------------------------- + +class BnPermissionController : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_IPERMISSION_CONTROLLER_H + diff --git a/third_party/android_frameworks_native/include/binder/IProcessInfoService.h b/third_party/android_frameworks_native/include/binder/IProcessInfoService.h new file mode 100644 index 00000000000000..dc62f457c72ccf --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IProcessInfoService.h @@ -0,0 +1,53 @@ +/* + * Copyright 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_I_PROCESS_INFO_SERVICE_H +#define ANDROID_I_PROCESS_INFO_SERVICE_H + +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IProcessInfoService : public IInterface { +public: + DECLARE_META_INTERFACE(ProcessInfoService); + + virtual status_t getProcessStatesFromPids( size_t length, + /*in*/ int32_t* pids, + /*out*/ int32_t* states) = 0; + + enum { + GET_PROCESS_STATES_FROM_PIDS = IBinder::FIRST_CALL_TRANSACTION, + }; +}; + +// ---------------------------------------------------------------------- + +class BnProcessInfoService : public BnInterface { +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_I_PROCESS_INFO_SERVICE_H diff --git a/third_party/android_frameworks_native/include/binder/IServiceManager.h b/third_party/android_frameworks_native/include/binder/IServiceManager.h new file mode 100644 index 00000000000000..2c297d64fb510e --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/IServiceManager.h @@ -0,0 +1,101 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +#ifndef ANDROID_ISERVICE_MANAGER_H +#define ANDROID_ISERVICE_MANAGER_H + +#include +#include +#include +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class IServiceManager : public IInterface +{ +public: + DECLARE_META_INTERFACE(ServiceManager); + + /** + * Retrieve an existing service, blocking for a few seconds + * if it doesn't yet exist. + */ + virtual sp getService( const String16& name) const = 0; + + /** + * Retrieve an existing service, non-blocking. + */ + virtual sp checkService( const String16& name) const = 0; + + /** + * Register a service. + */ + virtual status_t addService( const String16& name, + const sp& service, + bool allowIsolated = false) = 0; + + /** + * Return list of all existing services. + */ + virtual Vector listServices() = 0; + + enum { + GET_SERVICE_TRANSACTION = IBinder::FIRST_CALL_TRANSACTION, + CHECK_SERVICE_TRANSACTION, + ADD_SERVICE_TRANSACTION, + LIST_SERVICES_TRANSACTION, + }; +}; + +sp defaultServiceManager(); + +template +status_t getService(const String16& name, sp* outService) +{ + const sp sm = defaultServiceManager(); + if (sm != NULL) { + *outService = interface_cast(sm->getService(name)); + if ((*outService) != NULL) return NO_ERROR; + } + return NAME_NOT_FOUND; +} + +bool checkCallingPermission(const String16& permission); +bool checkCallingPermission(const String16& permission, + int32_t* outPid, int32_t* outUid); +bool checkPermission(const String16& permission, pid_t pid, uid_t uid); + + +// ---------------------------------------------------------------------- + +class BnServiceManager : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_ISERVICE_MANAGER_H + diff --git a/third_party/android_frameworks_native/include/binder/MemoryBase.h b/third_party/android_frameworks_native/include/binder/MemoryBase.h new file mode 100644 index 00000000000000..463e26d9772fa4 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/MemoryBase.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_MEMORY_BASE_H +#define ANDROID_MEMORY_BASE_H + +#include +#include + +#include + + +namespace android { + +// --------------------------------------------------------------------------- + +class MemoryBase : public BnMemory +{ +public: + MemoryBase(const sp& heap, ssize_t offset, size_t size); + virtual ~MemoryBase(); + virtual sp getMemory(ssize_t* offset, size_t* size) const; + +protected: + size_t getSize() const { return mSize; } + ssize_t getOffset() const { return mOffset; } + const sp& getHeap() const { return mHeap; } + +private: + size_t mSize; + ssize_t mOffset; + sp mHeap; +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_MEMORY_BASE_H diff --git a/third_party/android_frameworks_native/include/binder/MemoryDealer.h b/third_party/android_frameworks_native/include/binder/MemoryDealer.h new file mode 100644 index 00000000000000..aa415d5ac84117 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/MemoryDealer.h @@ -0,0 +1,61 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_MEMORY_DEALER_H +#define ANDROID_MEMORY_DEALER_H + + +#include +#include + +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class SimpleBestFitAllocator; + +// ---------------------------------------------------------------------------- + +class MemoryDealer : public RefBase +{ +public: + MemoryDealer(size_t size, const char* name = 0, + uint32_t flags = 0 /* or bits such as MemoryHeapBase::READ_ONLY */ ); + + virtual sp allocate(size_t size); + virtual void deallocate(size_t offset); + virtual void dump(const char* what) const; + + sp getMemoryHeap() const { return heap(); } + +protected: + virtual ~MemoryDealer(); + +private: + const sp& heap() const; + SimpleBestFitAllocator* allocator() const; + + sp mHeap; + SimpleBestFitAllocator* mAllocator; +}; + + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_MEMORY_DEALER_H diff --git a/third_party/android_frameworks_native/include/binder/MemoryHeapBase.h b/third_party/android_frameworks_native/include/binder/MemoryHeapBase.h new file mode 100644 index 00000000000000..ea9b66c4976349 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/MemoryHeapBase.h @@ -0,0 +1,103 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_MEMORY_HEAP_BASE_H +#define ANDROID_MEMORY_HEAP_BASE_H + +#include +#include + +#include + + +namespace android { + +// --------------------------------------------------------------------------- + +class MemoryHeapBase : public virtual BnMemoryHeap +{ +public: + enum { + READ_ONLY = IMemoryHeap::READ_ONLY, + // memory won't be mapped locally, but will be mapped in the remote + // process. + DONT_MAP_LOCALLY = 0x00000100, + NO_CACHING = 0x00000200 + }; + + /* + * maps the memory referenced by fd. but DOESN'T take ownership + * of the filedescriptor (it makes a copy with dup() + */ + MemoryHeapBase(int fd, size_t size, uint32_t flags = 0, uint32_t offset = 0); + + /* + * maps memory from the given device + */ + MemoryHeapBase(const char* device, size_t size = 0, uint32_t flags = 0); + + /* + * maps memory from ashmem, with the given name for debugging + */ + MemoryHeapBase(size_t size, uint32_t flags = 0, char const* name = NULL); + + virtual ~MemoryHeapBase(); + + /* implement IMemoryHeap interface */ + virtual int getHeapID() const; + + /* virtual address of the heap. returns MAP_FAILED in case of error */ + virtual void* getBase() const; + + virtual size_t getSize() const; + virtual uint32_t getFlags() const; + virtual uint32_t getOffset() const; + + const char* getDevice() const; + + /* this closes this heap -- use carefully */ + void dispose(); + + /* this is only needed as a workaround, use only if you know + * what you are doing */ + status_t setDevice(const char* device) { + if (mDevice == 0) + mDevice = device; + return mDevice ? NO_ERROR : ALREADY_EXISTS; + } + +protected: + MemoryHeapBase(); + // init() takes ownership of fd + status_t init(int fd, void *base, int size, + int flags = 0, const char* device = NULL); + +private: + status_t mapfd(int fd, size_t size, uint32_t offset = 0); + + int mFD; + size_t mSize; + void* mBase; + uint32_t mFlags; + const char* mDevice; + bool mNeedUnmap; + uint32_t mOffset; +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_MEMORY_HEAP_BASE_H diff --git a/third_party/android_frameworks_native/include/binder/MemoryHeapIon.h b/third_party/android_frameworks_native/include/binder/MemoryHeapIon.h new file mode 100644 index 00000000000000..7e059f4eac2627 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/MemoryHeapIon.h @@ -0,0 +1,68 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * Copyright 2011, Samsung Electronics Co. LTD + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +/*! + * \file MemoryHeapIon.h + * \brief header file for MemoryHeapIon + * \author MinGu, Jeon(mingu85.jeon) + * \date 2011/11/20 + * + * Revision History: + * - 2011/11/21 : MinGu, Jeon(mingu85.jeon)) \n + * Initial version + * - 2012/11/29 : MinGu, Jeon(mingu85.jeon)) \n + * Change name + */ + +#ifndef ANDROID_MEMORY_HEAP_ION_H +#define ANDROID_MEMORY_HEAP_ION_H + +#include +#include +#include + +#define MHB_ION_HEAP_SYSTEM_CONTIG_MASK (1 << 1) +#define MHB_ION_HEAP_EXYNOS_CONTIG_MASK (1 << 4) +#define MHB_ION_HEAP_EXYNOS_MASK (1 << 5) +#define MHB_ION_HEAP_SYSTEM_MASK (1 << 6) + +#define MHB_ION_FLAG_CACHED (1 << 16) +#define MHB_ION_FLAG_CACHED_NEEDS_SYNC (1 << 17) +#define MHB_ION_FLAG_PRESERVE_KMAP (1 << 18) + +#define MHB_ION_EXYNOS_VIDEO_MASK (1 << 21) +#define MHB_ION_EXYNOS_MFC_INPUT_MASK (1 << 25) +#define MHB_ION_EXYNOS_MFC_OUTPUT_MASK (1 << 26) +#define MHB_ION_EXYNOS_GSC_MASK (1 << 27) +#define MHB_ION_EXYNOS_FIMD_VIDEO_MASK (1 << 28) + +namespace android { + +class MemoryHeapIon : public MemoryHeapBase +{ +public: + enum { + USE_ION_FD = IMemoryHeap::USE_ION_FD + }; + MemoryHeapIon(size_t size, uint32_t flags = 0, char const* name = NULL); + MemoryHeapIon(int fd, size_t size, uint32_t flags = 0, uint32_t offset = 0); + ~MemoryHeapIon(); +private: + int mIonClient; +}; + +}; +#endif diff --git a/third_party/android_frameworks_native/include/binder/Parcel.h b/third_party/android_frameworks_native/include/binder/Parcel.h new file mode 100644 index 00000000000000..91ffae0ba3520b --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/Parcel.h @@ -0,0 +1,436 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_PARCEL_H +#define ANDROID_PARCEL_H + +#include +#include +#include +#include +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +template class Flattenable; +template class LightFlattenable; +class IBinder; +class IPCThreadState; +class ProcessState; +class String8; +class TextOutput; + +class Parcel { + friend class IPCThreadState; +public: + class ReadableBlob; + class WritableBlob; + + Parcel(); + ~Parcel(); + + const uint8_t* data() const; + size_t dataSize() const; + size_t dataAvail() const; + size_t dataPosition() const; + size_t dataCapacity() const; + + status_t setDataSize(size_t size); + void setDataPosition(size_t pos) const; + status_t setDataCapacity(size_t size); + + status_t setData(const uint8_t* buffer, size_t len); + + status_t appendFrom(const Parcel *parcel, + size_t start, size_t len); + + bool allowFds() const; + bool pushAllowFds(bool allowFds); + void restoreAllowFds(bool lastValue); + + bool hasFileDescriptors() const; + + // Writes the RPC header. + status_t writeInterfaceToken(const String16& interface); + + // Parses the RPC header, returning true if the interface name + // in the header matches the expected interface from the caller. + // + // Additionally, enforceInterface does part of the work of + // propagating the StrictMode policy mask, populating the current + // IPCThreadState, which as an optimization may optionally be + // passed in. + bool enforceInterface(const String16& interface, + IPCThreadState* threadState = NULL) const; + bool checkInterface(IBinder*) const; + + void freeData(); + +private: + const binder_size_t* objects() const; + +public: + size_t objectsCount() const; + + status_t errorCheck() const; + void setError(status_t err); + + status_t write(const void* data, size_t len); + void* writeInplace(size_t len); + status_t writeUnpadded(const void* data, size_t len); + status_t writeInt32(int32_t val); + status_t writeUint32(uint32_t val); + status_t writeInt64(int64_t val); + status_t writeUint64(uint64_t val); + status_t writeFloat(float val); + status_t writeDouble(double val); + status_t writeCString(const char* str); + status_t writeString8(const String8& str); + status_t writeString16(const String16& str); + status_t writeString16(const char16_t* str, size_t len); + status_t writeStrongBinder(const sp& val); + status_t writeWeakBinder(const wp& val); + status_t writeInt32Array(size_t len, const int32_t *val); + status_t writeByteArray(size_t len, const uint8_t *val); + + template + status_t write(const Flattenable& val); + + template + status_t write(const LightFlattenable& val); + + + // Place a native_handle into the parcel (the native_handle's file- + // descriptors are dup'ed, so it is safe to delete the native_handle + // when this function returns). + // Doesn't take ownership of the native_handle. + status_t writeNativeHandle(const native_handle* handle); + + // Place a file descriptor into the parcel. The given fd must remain + // valid for the lifetime of the parcel. + // The Parcel does not take ownership of the given fd unless you ask it to. + status_t writeFileDescriptor(int fd, bool takeOwnership = false); + + // Place a file descriptor into the parcel. A dup of the fd is made, which + // will be closed once the parcel is destroyed. + status_t writeDupFileDescriptor(int fd); + + // Writes a blob to the parcel. + // If the blob is small, then it is stored in-place, otherwise it is + // transferred by way of an anonymous shared memory region. Prefer sending + // immutable blobs if possible since they may be subsequently transferred between + // processes without further copying whereas mutable blobs always need to be copied. + // The caller should call release() on the blob after writing its contents. + status_t writeBlob(size_t len, bool mutableCopy, WritableBlob* outBlob); + + // Write an existing immutable blob file descriptor to the parcel. + // This allows the client to send the same blob to multiple processes + // as long as it keeps a dup of the blob file descriptor handy for later. + status_t writeDupImmutableBlobFileDescriptor(int fd); + + status_t writeObject(const flat_binder_object& val, bool nullMetaData); + + // Like Parcel.java's writeNoException(). Just writes a zero int32. + // Currently the native implementation doesn't do any of the StrictMode + // stack gathering and serialization that the Java implementation does. + status_t writeNoException(); + + void remove(size_t start, size_t amt); + + status_t read(void* outData, size_t len) const; + const void* readInplace(size_t len) const; + int32_t readInt32() const; + status_t readInt32(int32_t *pArg) const; + uint32_t readUint32() const; + status_t readUint32(uint32_t *pArg) const; + int64_t readInt64() const; + status_t readInt64(int64_t *pArg) const; + uint64_t readUint64() const; + status_t readUint64(uint64_t *pArg) const; + float readFloat() const; + status_t readFloat(float *pArg) const; + double readDouble() const; + status_t readDouble(double *pArg) const; + intptr_t readIntPtr() const; + status_t readIntPtr(intptr_t *pArg) const; + + const char* readCString() const; + String8 readString8() const; + String16 readString16() const; + const char16_t* readString16Inplace(size_t* outLen) const; + sp readStrongBinder() const; + wp readWeakBinder() const; + + template + status_t read(Flattenable& val) const; + + template + status_t read(LightFlattenable& val) const; + + // Like Parcel.java's readExceptionCode(). Reads the first int32 + // off of a Parcel's header, returning 0 or the negative error + // code on exceptions, but also deals with skipping over rich + // response headers. Callers should use this to read & parse the + // response headers rather than doing it by hand. + int32_t readExceptionCode() const; + + // Retrieve native_handle from the parcel. This returns a copy of the + // parcel's native_handle (the caller takes ownership). The caller + // must free the native_handle with native_handle_close() and + // native_handle_delete(). + native_handle* readNativeHandle() const; + + + // Retrieve a file descriptor from the parcel. This returns the raw fd + // in the parcel, which you do not own -- use dup() to get your own copy. + int readFileDescriptor() const; + + // Reads a blob from the parcel. + // The caller should call release() on the blob after reading its contents. + status_t readBlob(size_t len, ReadableBlob* outBlob) const; + + const flat_binder_object* readObject(bool nullMetaData) const; + + // Explicitly close all file descriptors in the parcel. + void closeFileDescriptors(); + + // Debugging: get metrics on current allocations. + static size_t getGlobalAllocSize(); + static size_t getGlobalAllocCount(); + +private: + typedef void (*release_func)(Parcel* parcel, + const uint8_t* data, size_t dataSize, + const binder_size_t* objects, size_t objectsSize, + void* cookie); + + uintptr_t ipcData() const; + size_t ipcDataSize() const; + uintptr_t ipcObjects() const; + size_t ipcObjectsCount() const; + void ipcSetDataReference(const uint8_t* data, size_t dataSize, + const binder_size_t* objects, size_t objectsCount, + release_func relFunc, void* relCookie); + +public: + void print(TextOutput& to, uint32_t flags = 0) const; + +private: + Parcel(const Parcel& o); + Parcel& operator=(const Parcel& o); + + status_t finishWrite(size_t len); + void releaseObjects(); + void acquireObjects(); + status_t growData(size_t len); + status_t restartWrite(size_t desired); + status_t continueWrite(size_t desired); + status_t writePointer(uintptr_t val); + status_t readPointer(uintptr_t *pArg) const; + uintptr_t readPointer() const; + void freeDataNoInit(); + void initState(); + void scanForFds() const; + + template + status_t readAligned(T *pArg) const; + + template T readAligned() const; + + template + status_t writeAligned(T val); + + status_t mError; + uint8_t* mData; + size_t mDataSize; + size_t mDataCapacity; + mutable size_t mDataPos; + binder_size_t* mObjects; + size_t mObjectsSize; + size_t mObjectsCapacity; + mutable size_t mNextObjectHint; + + mutable bool mFdsKnown; + mutable bool mHasFds; + bool mAllowFds; + + release_func mOwner; + void* mOwnerCookie; + + class Blob { + public: + Blob(); + ~Blob(); + + void clear(); + void release(); + inline size_t size() const { return mSize; } + inline int fd() const { return mFd; }; + inline bool isMutable() const { return mMutable; } + + protected: + void init(int fd, void* data, size_t size, bool isMutable); + + int mFd; // owned by parcel so not closed when released + void* mData; + size_t mSize; + bool mMutable; + }; + + class FlattenableHelperInterface { + protected: + ~FlattenableHelperInterface() { } + public: + virtual size_t getFlattenedSize() const = 0; + virtual size_t getFdCount() const = 0; + virtual status_t flatten(void* buffer, size_t size, int* fds, size_t count) const = 0; + virtual status_t unflatten(void const* buffer, size_t size, int const* fds, size_t count) = 0; + }; + + template + class FlattenableHelper : public FlattenableHelperInterface { + friend class Parcel; + const Flattenable& val; + explicit FlattenableHelper(const Flattenable& val) : val(val) { } + + public: + virtual size_t getFlattenedSize() const { + return val.getFlattenedSize(); + } + virtual size_t getFdCount() const { + return val.getFdCount(); + } + virtual status_t flatten(void* buffer, size_t size, int* fds, size_t count) const { + return val.flatten(buffer, size, fds, count); + } + virtual status_t unflatten(void const* buffer, size_t size, int const* fds, size_t count) { + return const_cast&>(val).unflatten(buffer, size, fds, count); + } + }; + status_t write(const FlattenableHelperInterface& val); + status_t read(FlattenableHelperInterface& val) const; + +public: + class ReadableBlob : public Blob { + friend class Parcel; + public: + inline const void* data() const { return mData; } + inline void* mutableData() { return isMutable() ? mData : NULL; } + }; + + class WritableBlob : public Blob { + friend class Parcel; + public: + inline void* data() { return mData; } + }; + +#ifndef DISABLE_ASHMEM_TRACKING +private: + size_t mOpenAshmemSize; +#endif + +public: + // TODO: Remove once ABI can be changed. + size_t getBlobAshmemSize() const; + size_t getOpenAshmemSize() const; +}; + +// --------------------------------------------------------------------------- + +template +status_t Parcel::write(const Flattenable& val) { + const FlattenableHelper helper(val); + return write(helper); +} + +template +status_t Parcel::write(const LightFlattenable& val) { + size_t size(val.getFlattenedSize()); + if (!val.isFixedSize()) { + status_t err = writeInt32(size); + if (err != NO_ERROR) { + return err; + } + } + if (size) { + void* buffer = writeInplace(size); + if (buffer == NULL) + return NO_MEMORY; + return val.flatten(buffer, size); + } + return NO_ERROR; +} + +template +status_t Parcel::read(Flattenable& val) const { + FlattenableHelper helper(val); + return read(helper); +} + +template +status_t Parcel::read(LightFlattenable& val) const { + size_t size; + if (val.isFixedSize()) { + size = val.getFlattenedSize(); + } else { + int32_t s; + status_t err = readInt32(&s); + if (err != NO_ERROR) { + return err; + } + size = s; + } + if (size) { + void const* buffer = readInplace(size); + return buffer == NULL ? NO_MEMORY : + val.unflatten(buffer, size); + } + return NO_ERROR; +} + +// --------------------------------------------------------------------------- + +inline TextOutput& operator<<(TextOutput& to, const Parcel& parcel) +{ + parcel.print(to); + return to; +} + +// --------------------------------------------------------------------------- + +// Generic acquire and release of objects. +void acquire_object(const sp& proc, + const flat_binder_object& obj, const void* who); +void release_object(const sp& proc, + const flat_binder_object& obj, const void* who); + +void flatten_binder(const sp& proc, + const sp& binder, flat_binder_object* out); +void flatten_binder(const sp& proc, + const wp& binder, flat_binder_object* out); +status_t unflatten_binder(const sp& proc, + const flat_binder_object& flat, sp* out); +status_t unflatten_binder(const sp& proc, + const flat_binder_object& flat, wp* out); + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_PARCEL_H diff --git a/third_party/android_frameworks_native/include/binder/PermissionCache.h b/third_party/android_frameworks_native/include/binder/PermissionCache.h new file mode 100644 index 00000000000000..bcdf0c291434ed --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/PermissionCache.h @@ -0,0 +1,80 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef BINDER_PERMISSION_H +#define BINDER_PERMISSION_H + +#include +#include + +#include +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +/* + * PermissionCache caches permission checks for a given uid. + * + * Currently the cache is not updated when there is a permission change, + * for instance when an application is uninstalled. + * + * IMPORTANT: for the reason stated above, only system permissions are safe + * to cache. This restriction may be lifted at a later time. + * + */ + +class PermissionCache : Singleton { + struct Entry { + String16 name; + uid_t uid; + bool granted; + inline bool operator < (const Entry& e) const { + return (uid == e.uid) ? (name < e.name) : (uid < e.uid); + } + }; + mutable Mutex mLock; + // we pool all the permission names we see, as many permissions checks + // will have identical names + SortedVector< String16 > mPermissionNamesPool; + // this is our cache per say. it stores pooled names. + SortedVector< Entry > mCache; + + // free the whole cache, but keep the permission name pool + void purge(); + + status_t check(bool* granted, + const String16& permission, uid_t uid) const; + + void cache(const String16& permission, uid_t uid, bool granted); + +public: + PermissionCache(); + + static bool checkCallingPermission(const String16& permission); + + static bool checkCallingPermission(const String16& permission, + int32_t* outPid, int32_t* outUid); + + static bool checkPermission(const String16& permission, + pid_t pid, uid_t uid); +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif /* BINDER_PERMISSION_H */ diff --git a/third_party/android_frameworks_native/include/binder/ProcessInfoService.h b/third_party/android_frameworks_native/include/binder/ProcessInfoService.h new file mode 100644 index 00000000000000..c5ead2067657a0 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/ProcessInfoService.h @@ -0,0 +1,65 @@ +/* + * Copyright 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_PROCESS_INFO_SERVICE_H +#define ANDROID_PROCESS_INFO_SERVICE_H + +#include +#include +#include +#include + +namespace android { + +// ---------------------------------------------------------------------- + +class ProcessInfoService : public Singleton { + + friend class Singleton; + sp mProcessInfoService; + Mutex mProcessInfoLock; + + ProcessInfoService(); + + status_t getProcessStatesImpl(size_t length, /*in*/ int32_t* pids, /*out*/ int32_t* states); + void updateBinderLocked(); + + static const int BINDER_ATTEMPT_LIMIT = 5; + +public: + + /** + * For each PID in the given "pids" input array, write the current process state + * for that process into the "states" output array, or + * ActivityManager.PROCESS_STATE_NONEXISTENT * to indicate that no process with the given PID + * exists. + * + * Returns NO_ERROR if this operation was successful, or a negative error code otherwise. + */ + static status_t getProcessStatesFromPids(size_t length, /*in*/ int32_t* pids, + /*out*/ int32_t* states) { + return ProcessInfoService::getInstance().getProcessStatesImpl(length, /*in*/ pids, + /*out*/ states); + } + +}; + +// ---------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_PROCESS_INFO_SERVICE_H + diff --git a/third_party/android_frameworks_native/include/binder/ProcessState.h b/third_party/android_frameworks_native/include/binder/ProcessState.h new file mode 100644 index 00000000000000..f9edc2a691fc02 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/ProcessState.h @@ -0,0 +1,116 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_PROCESS_STATE_H +#define ANDROID_PROCESS_STATE_H + +#include +#include +#include +#include + +#include + +#include + +// --------------------------------------------------------------------------- +namespace android { + +class IPCThreadState; + +class ProcessState : public virtual RefBase +{ +public: + static sp self(); + + void setContextObject(const sp& object); + sp getContextObject(const sp& caller); + + void setContextObject(const sp& object, + const String16& name); + sp getContextObject(const String16& name, + const sp& caller); + + void startThreadPool(); + + typedef bool (*context_check_func)(const String16& name, + const sp& caller, + void* userData); + + bool isContextManager(void) const; + bool becomeContextManager( + context_check_func checkFunc, + void* userData); + + sp getStrongProxyForHandle(int32_t handle); + wp getWeakProxyForHandle(int32_t handle); + void expungeHandle(int32_t handle, IBinder* binder); + + void spawnPooledThread(bool isMain); + + status_t setThreadPoolMaxThreadCount(size_t maxThreads); + void giveThreadPoolName(); + +private: + friend class IPCThreadState; + + ProcessState(); + ~ProcessState(); + + ProcessState(const ProcessState& o); + ProcessState& operator=(const ProcessState& o); + String8 makeBinderThreadName(); + + struct handle_entry { + IBinder* binder; + RefBase::weakref_type* refs; + }; + + handle_entry* lookupHandleLocked(int32_t handle); + + int mDriverFD; + void* mVMStart; + + // Protects thread count variable below. + pthread_mutex_t mThreadCountLock; + pthread_cond_t mThreadCountDecrement; + // Number of binder threads current executing a command. + size_t mExecutingThreadsCount; + // Maximum number for binder threads allowed for this process. + size_t mMaxThreads; + + mutable Mutex mLock; // protects everything below. + + VectormHandleToObject; + + bool mManagesContexts; + context_check_func mBinderContextCheckFunc; + void* mBinderContextUserData; + + KeyedVector > + mContexts; + + + String8 mRootDir; + bool mThreadPoolStarted; + volatile int32_t mThreadPoolSeq; +}; + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_PROCESS_STATE_H diff --git a/third_party/android_frameworks_native/include/binder/TextOutput.h b/third_party/android_frameworks_native/include/binder/TextOutput.h new file mode 100644 index 00000000000000..974a194d8c4631 --- /dev/null +++ b/third_party/android_frameworks_native/include/binder/TextOutput.h @@ -0,0 +1,195 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_TEXTOUTPUT_H +#define ANDROID_TEXTOUTPUT_H + +#include + +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +class String8; +class String16; + +class TextOutput +{ +public: + TextOutput(); + virtual ~TextOutput(); + + virtual status_t print(const char* txt, size_t len) = 0; + virtual void moveIndent(int delta) = 0; + + class Bundle { + public: + inline Bundle(TextOutput& to) : mTO(to) { to.pushBundle(); } + inline ~Bundle() { mTO.popBundle(); } + private: + TextOutput& mTO; + }; + + virtual void pushBundle() = 0; + virtual void popBundle() = 0; +}; + +// --------------------------------------------------------------------------- + +// Text output stream for printing to the log (via utils/Log.h). +extern TextOutput& alog; + +// Text output stream for printing to stdout. +extern TextOutput& aout; + +// Text output stream for printing to stderr. +extern TextOutput& aerr; + +typedef TextOutput& (*TextOutputManipFunc)(TextOutput&); + +TextOutput& endl(TextOutput& to); +TextOutput& indent(TextOutput& to); +TextOutput& dedent(TextOutput& to); + +TextOutput& operator<<(TextOutput& to, const char* str); +TextOutput& operator<<(TextOutput& to, char); // writes raw character +TextOutput& operator<<(TextOutput& to, bool); +TextOutput& operator<<(TextOutput& to, int); +TextOutput& operator<<(TextOutput& to, long); +TextOutput& operator<<(TextOutput& to, unsigned int); +TextOutput& operator<<(TextOutput& to, unsigned long); +TextOutput& operator<<(TextOutput& to, long long); +TextOutput& operator<<(TextOutput& to, unsigned long long); +TextOutput& operator<<(TextOutput& to, float); +TextOutput& operator<<(TextOutput& to, double); +TextOutput& operator<<(TextOutput& to, TextOutputManipFunc func); +TextOutput& operator<<(TextOutput& to, const void*); +TextOutput& operator<<(TextOutput& to, const String8& val); +TextOutput& operator<<(TextOutput& to, const String16& val); + +class TypeCode +{ +public: + inline TypeCode(uint32_t code); + inline ~TypeCode(); + + inline uint32_t typeCode() const; + +private: + uint32_t mCode; +}; + +TextOutput& operator<<(TextOutput& to, const TypeCode& val); + +class HexDump +{ +public: + HexDump(const void *buf, size_t size, size_t bytesPerLine=16); + inline ~HexDump(); + + inline HexDump& setBytesPerLine(size_t bytesPerLine); + inline HexDump& setSingleLineCutoff(int32_t bytes); + inline HexDump& setAlignment(size_t alignment); + inline HexDump& setCArrayStyle(bool enabled); + + inline const void* buffer() const; + inline size_t size() const; + inline size_t bytesPerLine() const; + inline int32_t singleLineCutoff() const; + inline size_t alignment() const; + inline bool carrayStyle() const; + +private: + const void* mBuffer; + size_t mSize; + size_t mBytesPerLine; + int32_t mSingleLineCutoff; + size_t mAlignment; + bool mCArrayStyle; +}; + +TextOutput& operator<<(TextOutput& to, const HexDump& val); + +// --------------------------------------------------------------------------- +// No user servicable parts below. + +inline TextOutput& endl(TextOutput& to) +{ + to.print("\n", 1); + return to; +} + +inline TextOutput& indent(TextOutput& to) +{ + to.moveIndent(1); + return to; +} + +inline TextOutput& dedent(TextOutput& to) +{ + to.moveIndent(-1); + return to; +} + +inline TextOutput& operator<<(TextOutput& to, const char* str) +{ + to.print(str, strlen(str)); + return to; +} + +inline TextOutput& operator<<(TextOutput& to, char c) +{ + to.print(&c, 1); + return to; +} + +inline TextOutput& operator<<(TextOutput& to, TextOutputManipFunc func) +{ + return (*func)(to); +} + +inline TypeCode::TypeCode(uint32_t code) : mCode(code) { } +inline TypeCode::~TypeCode() { } +inline uint32_t TypeCode::typeCode() const { return mCode; } + +inline HexDump::~HexDump() { } + +inline HexDump& HexDump::setBytesPerLine(size_t bytesPerLine) { + mBytesPerLine = bytesPerLine; return *this; +} +inline HexDump& HexDump::setSingleLineCutoff(int32_t bytes) { + mSingleLineCutoff = bytes; return *this; +} +inline HexDump& HexDump::setAlignment(size_t alignment) { + mAlignment = alignment; return *this; +} +inline HexDump& HexDump::setCArrayStyle(bool enabled) { + mCArrayStyle = enabled; return *this; +} + +inline const void* HexDump::buffer() const { return mBuffer; } +inline size_t HexDump::size() const { return mSize; } +inline size_t HexDump::bytesPerLine() const { return mBytesPerLine; } +inline int32_t HexDump::singleLineCutoff() const { return mSingleLineCutoff; } +inline size_t HexDump::alignment() const { return mAlignment; } +inline bool HexDump::carrayStyle() const { return mCArrayStyle; } + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_TEXTOUTPUT_H diff --git a/third_party/android_frameworks_native/include/gui/BitTube.h b/third_party/android_frameworks_native/include/gui/BitTube.h new file mode 100644 index 00000000000000..3ecac52ad766f7 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BitTube.h @@ -0,0 +1,95 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SENSOR_CHANNEL_H +#define ANDROID_GUI_SENSOR_CHANNEL_H + +#include +#include + +#include +#include +#include + + +namespace android { +// ---------------------------------------------------------------------------- +class Parcel; + +class BitTube : public RefBase +{ +public: + + // creates a BitTube with a default (4KB) send buffer + BitTube(); + + // creates a BitTube with a a specified send and receive buffer size + explicit BitTube(size_t bufsize); + + explicit BitTube(const Parcel& data); + virtual ~BitTube(); + + // check state after construction + status_t initCheck() const; + + // get receive file-descriptor + int getFd() const; + + // get the send file-descriptor. + int getSendFd() const; + + // send objects (sized blobs). All objects are guaranteed to be written or the call fails. + template + static ssize_t sendObjects(const sp& tube, + T const* events, size_t count) { + return sendObjects(tube, events, count, sizeof(T)); + } + + // receive objects (sized blobs). If the receiving buffer isn't large enough, + // excess messages are silently discarded. + template + static ssize_t recvObjects(const sp& tube, + T* events, size_t count) { + return recvObjects(tube, events, count, sizeof(T)); + } + + // parcels this BitTube + status_t writeToParcel(Parcel* reply) const; + +private: + void init(size_t rcvbuf, size_t sndbuf); + + // send a message. The write is guaranteed to send the whole message or fail. + ssize_t write(void const* vaddr, size_t size); + + // receive a message. the passed buffer must be at least as large as the + // write call used to send the message, excess data is silently discarded. + ssize_t read(void* vaddr, size_t size); + + int mSendFd; + mutable int mReceiveFd; + + static ssize_t sendObjects(const sp& tube, + void const* events, size_t count, size_t objSize); + + static ssize_t recvObjects(const sp& tube, + void* events, size_t count, size_t objSize); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_SENSOR_CHANNEL_H diff --git a/third_party/android_frameworks_native/include/gui/BufferItem.h b/third_party/android_frameworks_native/include/gui/BufferItem.h new file mode 100644 index 00000000000000..145efe6f602b84 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferItem.h @@ -0,0 +1,130 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERITEM_H +#define ANDROID_GUI_BUFFERITEM_H + +#include +#include + +#include +#include + +#include + +#include +#include + +namespace android { + +class Fence; +class GraphicBuffer; + +class BufferItem : public Flattenable { + friend class Flattenable; + size_t getPodSize() const; + size_t getFlattenedSize() const; + size_t getFdCount() const; + status_t flatten(void*& buffer, size_t& size, int*& fds, size_t& count) const; + status_t unflatten(void const*& buffer, size_t& size, int const*& fds, size_t& count); + + public: + // The default value of mBuf, used to indicate this doesn't correspond to a slot. + enum { INVALID_BUFFER_SLOT = -1 }; + BufferItem(); + ~BufferItem(); + + static const char* scalingModeName(uint32_t scalingMode); + + // mGraphicBuffer points to the buffer allocated for this slot, or is NULL + // if the buffer in this slot has been acquired in the past (see + // BufferSlot.mAcquireCalled). + sp mGraphicBuffer; + + // mFence is a fence that will signal when the buffer is idle. + sp mFence; + + // mCrop is the current crop rectangle for this buffer slot. + Rect mCrop; + + // mTransform is the current transform flags for this buffer slot. + // refer to NATIVE_WINDOW_TRANSFORM_* in + uint32_t mTransform; + + // mScalingMode is the current scaling mode for this buffer slot. + // refer to NATIVE_WINDOW_SCALING_* in + uint32_t mScalingMode; + + // mTimestamp is the current timestamp for this buffer slot. This gets + // to set by queueBuffer each time this slot is queued. This value + // is guaranteed to be monotonically increasing for each newly + // acquired buffer. + union { + int64_t mTimestamp; + struct { + uint32_t mTimestampLo; + uint32_t mTimestampHi; + }; + }; + + // mIsAutoTimestamp indicates whether mTimestamp was generated + // automatically when the buffer was queued. + bool mIsAutoTimestamp; + + // mDataSpace is the current dataSpace value for this buffer slot. This gets + // set by queueBuffer each time this slot is queued. The meaning of the + // dataSpace is format-dependent. + android_dataspace mDataSpace; + + // mFrameNumber is the number of the queued frame for this slot. + union { + uint64_t mFrameNumber; + struct { + uint32_t mFrameNumberLo; + uint32_t mFrameNumberHi; + }; + }; + + union { + // mSlot is the slot index of this buffer (default INVALID_BUFFER_SLOT). + int mSlot; + + // mBuf is the former name for mSlot + int mBuf; + }; + + // mIsDroppable whether this buffer was queued with the + // property that it can be replaced by a new buffer for the purpose of + // making sure dequeueBuffer() won't block. + // i.e.: was the BufferQueue in "mDequeueBufferCannotBlock" when this buffer + // was queued. + bool mIsDroppable; + + // Indicates whether this buffer has been seen by a consumer yet + bool mAcquireCalled; + + // Indicates this buffer must be transformed by the inverse transform of the screen + // it is displayed onto. This is applied after mTransform. + bool mTransformToDisplayInverse; + + // Describes the portion of the surface that has been modified since the + // previous frame + Region mSurfaceDamage; +}; + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/BufferItemConsumer.h b/third_party/android_frameworks_native/include/gui/BufferItemConsumer.h new file mode 100644 index 00000000000000..56c7a3f46382f2 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferItemConsumer.h @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERITEMCONSUMER_H +#define ANDROID_GUI_BUFFERITEMCONSUMER_H + +#include + +#include + +#include +#include +#include + +#define ANDROID_GRAPHICS_BUFFERITEMCONSUMER_JNI_ID "mBufferItemConsumer" + +namespace android { + +class BufferQueue; + +/** + * BufferItemConsumer is a BufferQueue consumer endpoint that allows clients + * access to the whole BufferItem entry from BufferQueue. Multiple buffers may + * be acquired at once, to be used concurrently by the client. This consumer can + * operate either in synchronous or asynchronous mode. + */ +class BufferItemConsumer: public ConsumerBase +{ + public: + typedef ConsumerBase::FrameAvailableListener FrameAvailableListener; + + enum { DEFAULT_MAX_BUFFERS = -1 }; + enum { INVALID_BUFFER_SLOT = BufferQueue::INVALID_BUFFER_SLOT }; + enum { NO_BUFFER_AVAILABLE = BufferQueue::NO_BUFFER_AVAILABLE }; + + // Create a new buffer item consumer. The consumerUsage parameter determines + // the consumer usage flags passed to the graphics allocator. The + // bufferCount parameter specifies how many buffers can be locked for user + // access at the same time. + // controlledByApp tells whether this consumer is controlled by the + // application. + BufferItemConsumer(const sp& consumer, + uint32_t consumerUsage, int bufferCount = DEFAULT_MAX_BUFFERS, + bool controlledByApp = false); + + virtual ~BufferItemConsumer(); + + // set the name of the BufferItemConsumer that will be used to identify it in + // log messages. + void setName(const String8& name); + + // Gets the next graphics buffer from the producer, filling out the + // passed-in BufferItem structure. Returns NO_BUFFER_AVAILABLE if the queue + // of buffers is empty, and INVALID_OPERATION if the maximum number of + // buffers is already acquired. + // + // Only a fixed number of buffers can be acquired at a time, determined by + // the construction-time bufferCount parameter. If INVALID_OPERATION is + // returned by acquireBuffer, then old buffers must be returned to the + // queue by calling releaseBuffer before more buffers can be acquired. + // + // If waitForFence is true, and the acquired BufferItem has a valid fence object, + // acquireBuffer will wait on the fence with no timeout before returning. + status_t acquireBuffer(BufferItem* item, nsecs_t presentWhen, + bool waitForFence = true); + + // Returns an acquired buffer to the queue, allowing it to be reused. Since + // only a fixed number of buffers may be acquired at a time, old buffers + // must be released by calling releaseBuffer to ensure new buffers can be + // acquired by acquireBuffer. Once a BufferItem is released, the caller must + // not access any members of the BufferItem, and should immediately remove + // all of its references to the BufferItem itself. + status_t releaseBuffer(const BufferItem &item, + const sp& releaseFence = Fence::NO_FENCE); + +}; + +} // namespace android + +#endif // ANDROID_GUI_CPUCONSUMER_H diff --git a/third_party/android_frameworks_native/include/gui/BufferQueue.h b/third_party/android_frameworks_native/include/gui/BufferQueue.h new file mode 100644 index 00000000000000..09300a20c96fd0 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferQueue.h @@ -0,0 +1,89 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERQUEUE_H +#define ANDROID_GUI_BUFFERQUEUE_H + +#include +#include +#include +#include +#include + +// These are only required to keep other parts of the framework with incomplete +// dependencies building successfully +#include + +namespace android { + +class BufferQueue { +public: + // BufferQueue will keep track of at most this value of buffers. + // Attempts at runtime to increase the number of buffers past this will fail. + enum { NUM_BUFFER_SLOTS = BufferQueueDefs::NUM_BUFFER_SLOTS }; + // Used as a placeholder slot# when the value isn't pointing to an existing buffer. + enum { INVALID_BUFFER_SLOT = BufferItem::INVALID_BUFFER_SLOT }; + // Alias to -- please scope from there in future code! + enum { + NO_BUFFER_AVAILABLE = IGraphicBufferConsumer::NO_BUFFER_AVAILABLE, + PRESENT_LATER = IGraphicBufferConsumer::PRESENT_LATER, + }; + + // When in async mode we reserve two slots in order to guarantee that the + // producer and consumer can run asynchronously. + enum { MAX_MAX_ACQUIRED_BUFFERS = NUM_BUFFER_SLOTS - 2 }; + + // for backward source compatibility + typedef ::android::ConsumerListener ConsumerListener; + + // ProxyConsumerListener is a ConsumerListener implementation that keeps a weak + // reference to the actual consumer object. It forwards all calls to that + // consumer object so long as it exists. + // + // This class exists to avoid having a circular reference between the + // BufferQueue object and the consumer object. The reason this can't be a weak + // reference in the BufferQueue class is because we're planning to expose the + // consumer side of a BufferQueue as a binder interface, which doesn't support + // weak references. + class ProxyConsumerListener : public BnConsumerListener { + public: + ProxyConsumerListener(const wp& consumerListener); + virtual ~ProxyConsumerListener(); + virtual void onFrameAvailable(const BufferItem& item) override; + virtual void onFrameReplaced(const BufferItem& item) override; + virtual void onBuffersReleased() override; + virtual void onSidebandStreamChanged() override; + private: + // mConsumerListener is a weak reference to the IConsumerListener. This is + // the raison d'etre of ProxyConsumerListener. + wp mConsumerListener; + }; + + // BufferQueue manages a pool of gralloc memory slots to be used by + // producers and consumers. allocator is used to allocate all the + // needed gralloc buffers. + static void createBufferQueue(sp* outProducer, + sp* outConsumer, + const sp& allocator = NULL); + +private: + BufferQueue(); // Create through createBufferQueue +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_BUFFERQUEUE_H diff --git a/third_party/android_frameworks_native/include/gui/BufferQueueConsumer.h b/third_party/android_frameworks_native/include/gui/BufferQueueConsumer.h new file mode 100644 index 00000000000000..cde302f8a61f67 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferQueueConsumer.h @@ -0,0 +1,187 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERQUEUECONSUMER_H +#define ANDROID_GUI_BUFFERQUEUECONSUMER_H + +#include +#include + +#include +#include + +namespace android { + +class BufferQueueCore; + +class BufferQueueConsumer : public BnGraphicBufferConsumer { + +public: + BufferQueueConsumer(const sp& core); + virtual ~BufferQueueConsumer(); + + // acquireBuffer attempts to acquire ownership of the next pending buffer in + // the BufferQueue. If no buffer is pending then it returns + // NO_BUFFER_AVAILABLE. If a buffer is successfully acquired, the + // information about the buffer is returned in BufferItem. If the buffer + // returned had previously been acquired then the BufferItem::mGraphicBuffer + // field of buffer is set to NULL and it is assumed that the consumer still + // holds a reference to the buffer. + // + // If expectedPresent is nonzero, it indicates the time when the buffer + // will be displayed on screen. If the buffer's timestamp is farther in the + // future, the buffer won't be acquired, and PRESENT_LATER will be + // returned. The presentation time is in nanoseconds, and the time base + // is CLOCK_MONOTONIC. + virtual status_t acquireBuffer(BufferItem* outBuffer, + nsecs_t expectedPresent, uint64_t maxFrameNumber = 0) override; + + // See IGraphicBufferConsumer::detachBuffer + virtual status_t detachBuffer(int slot); + + // See IGraphicBufferConsumer::attachBuffer + virtual status_t attachBuffer(int* slot, const sp& buffer); + + // releaseBuffer releases a buffer slot from the consumer back to the + // BufferQueue. This may be done while the buffer's contents are still + // being accessed. The fence will signal when the buffer is no longer + // in use. frameNumber is used to indentify the exact buffer returned. + // + // If releaseBuffer returns STALE_BUFFER_SLOT, then the consumer must free + // any references to the just-released buffer that it might have, as if it + // had received a onBuffersReleased() call with a mask set for the released + // buffer. + // + // Note that the dependencies on EGL will be removed once we switch to using + // the Android HW Sync HAL. + virtual status_t releaseBuffer(int slot, uint64_t frameNumber, + const sp& releaseFence, EGLDisplay display, + EGLSyncKHR fence); + + // connect connects a consumer to the BufferQueue. Only one + // consumer may be connected, and when that consumer disconnects the + // BufferQueue is placed into the "abandoned" state, causing most + // interactions with the BufferQueue by the producer to fail. + // controlledByApp indicates whether the consumer is controlled by + // the application. + // + // consumerListener may not be NULL. + virtual status_t connect(const sp& consumerListener, + bool controlledByApp); + + // disconnect disconnects a consumer from the BufferQueue. All + // buffers will be freed and the BufferQueue is placed in the "abandoned" + // state, causing most interactions with the BufferQueue by the producer to + // fail. + virtual status_t disconnect(); + + // getReleasedBuffers sets the value pointed to by outSlotMask to a bit mask + // indicating which buffer slots have been released by the BufferQueue + // but have not yet been released by the consumer. + // + // This should be called from the onBuffersReleased() callback. + virtual status_t getReleasedBuffers(uint64_t* outSlotMask); + + // setDefaultBufferSize is used to set the size of buffers returned by + // dequeueBuffer when a width and height of zero is requested. Default + // is 1x1. + virtual status_t setDefaultBufferSize(uint32_t width, uint32_t height); + + // setDefaultMaxBufferCount sets the default value for the maximum buffer + // count (the initial default is 2). If the producer has requested a + // buffer count using setBufferCount, the default buffer count will only + // take effect if the producer sets the count back to zero. + // + // The count must be between 2 and NUM_BUFFER_SLOTS, inclusive. + virtual status_t setDefaultMaxBufferCount(int bufferCount); + + // disableAsyncBuffer disables the extra buffer used in async mode + // (when both producer and consumer have set their "isControlledByApp" + // flag) and has dequeueBuffer() return WOULD_BLOCK instead. + // + // This can only be called before connect(). + virtual status_t disableAsyncBuffer(); + + // setMaxAcquiredBufferCount sets the maximum number of buffers that can + // be acquired by the consumer at one time (default 1). This call will + // fail if a producer is connected to the BufferQueue. + virtual status_t setMaxAcquiredBufferCount(int maxAcquiredBuffers); + + // setConsumerName sets the name used in logging + virtual void setConsumerName(const String8& name); + + // setDefaultBufferFormat allows the BufferQueue to create + // GraphicBuffers of a defaultFormat if no format is specified + // in dequeueBuffer. The initial default is HAL_PIXEL_FORMAT_RGBA_8888. + virtual status_t setDefaultBufferFormat(PixelFormat defaultFormat); + + // setDefaultBufferDataSpace allows the BufferQueue to create + // GraphicBuffers of a defaultDataSpace if no data space is specified + // in queueBuffer. + // The initial default is HAL_DATASPACE_UNKNOWN + virtual status_t setDefaultBufferDataSpace( + android_dataspace defaultDataSpace); + + // setConsumerUsageBits will turn on additional usage bits for dequeueBuffer. + // These are merged with the bits passed to dequeueBuffer. The values are + // enumerated in gralloc.h, e.g. GRALLOC_USAGE_HW_RENDER; the default is 0. + virtual status_t setConsumerUsageBits(uint32_t usage); + + // setTransformHint bakes in rotation to buffers so overlays can be used. + // The values are enumerated in window.h, e.g. + // NATIVE_WINDOW_TRANSFORM_ROT_90. The default is 0 (no transform). + virtual status_t setTransformHint(uint32_t hint); + + // Retrieve the sideband buffer stream, if any. + virtual sp getSidebandStream() const; + + // dump our state in a String + virtual void dump(String8& result, const char* prefix) const; + + // Functions required for backwards compatibility. + // These will be modified/renamed in IGraphicBufferConsumer and will be + // removed from this class at that time. See b/13306289. + + virtual status_t releaseBuffer(int buf, uint64_t frameNumber, + EGLDisplay display, EGLSyncKHR fence, + const sp& releaseFence) { + return releaseBuffer(buf, frameNumber, releaseFence, display, fence); + } + + virtual status_t consumerConnect(const sp& consumer, + bool controlledByApp) { + return connect(consumer, controlledByApp); + } + + virtual status_t consumerDisconnect() { return disconnect(); } + + // End functions required for backwards compatibility + +private: + sp mCore; + + // This references mCore->mSlots. Lock mCore->mMutex while accessing. + BufferQueueDefs::SlotsType& mSlots; + + // This is a cached copy of the name stored in the BufferQueueCore. + // It's updated during setConsumerName. + String8 mConsumerName; + +}; // class BufferQueueConsumer + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/BufferQueueCore.h b/third_party/android_frameworks_native/include/gui/BufferQueueCore.h new file mode 100644 index 00000000000000..99134ea5018a45 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferQueueCore.h @@ -0,0 +1,287 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERQUEUECORE_H +#define ANDROID_GUI_BUFFERQUEUECORE_H + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#define BQ_LOGV(x, ...) ALOGV("[%s] " x, mConsumerName.string(), ##__VA_ARGS__) +#define BQ_LOGD(x, ...) ALOGD("[%s] " x, mConsumerName.string(), ##__VA_ARGS__) +#define BQ_LOGI(x, ...) ALOGI("[%s] " x, mConsumerName.string(), ##__VA_ARGS__) +#define BQ_LOGW(x, ...) ALOGW("[%s] " x, mConsumerName.string(), ##__VA_ARGS__) +#define BQ_LOGE(x, ...) ALOGE("[%s] " x, mConsumerName.string(), ##__VA_ARGS__) + +#define ATRACE_BUFFER_INDEX(index) \ + if (ATRACE_ENABLED()) { \ + char ___traceBuf[1024]; \ + snprintf(___traceBuf, 1024, "%s: %d", \ + mCore->mConsumerName.string(), (index)); \ + android::ScopedTrace ___bufTracer(ATRACE_TAG, ___traceBuf); \ + } + +namespace android { + +class IConsumerListener; +class IGraphicBufferAlloc; +class IProducerListener; + +class BufferQueueCore : public virtual RefBase { + + friend class BufferQueueProducer; + friend class BufferQueueConsumer; + +public: + // Used as a placeholder slot number when the value isn't pointing to an + // existing buffer. + enum { INVALID_BUFFER_SLOT = BufferItem::INVALID_BUFFER_SLOT }; + + // We reserve two slots in order to guarantee that the producer and + // consumer can run asynchronously. + enum { MAX_MAX_ACQUIRED_BUFFERS = BufferQueueDefs::NUM_BUFFER_SLOTS - 2 }; + + // The default API number used to indicate that no producer is connected + enum { NO_CONNECTED_API = 0 }; + + typedef Vector Fifo; + + // BufferQueueCore manages a pool of gralloc memory slots to be used by + // producers and consumers. allocator is used to allocate all the needed + // gralloc buffers. + BufferQueueCore(const sp& allocator = NULL); + virtual ~BufferQueueCore(); + +private: + // Dump our state in a string + void dump(String8& result, const char* prefix) const; + + // getMinUndequeuedBufferCountLocked returns the minimum number of buffers + // that must remain in a state other than DEQUEUED. The async parameter + // tells whether we're in asynchronous mode. + int getMinUndequeuedBufferCountLocked(bool async) const; + + // getMinMaxBufferCountLocked returns the minimum number of buffers allowed + // given the current BufferQueue state. The async parameter tells whether + // we're in asynchonous mode. + int getMinMaxBufferCountLocked(bool async) const; + + // getMaxBufferCountLocked returns the maximum number of buffers that can be + // allocated at once. This value depends on the following member variables: + // + // mDequeueBufferCannotBlock + // mMaxAcquiredBufferCount + // mDefaultMaxBufferCount + // mOverrideMaxBufferCount + // async parameter + // + // Any time one of these member variables is changed while a producer is + // connected, mDequeueCondition must be broadcast. + int getMaxBufferCountLocked(bool async) const; + + // setDefaultMaxBufferCountLocked sets the maximum number of buffer slots + // that will be used if the producer does not override the buffer slot + // count. The count must be between 2 and NUM_BUFFER_SLOTS, inclusive. The + // initial default is 2. + status_t setDefaultMaxBufferCountLocked(int count); + + // freeBufferLocked frees the GraphicBuffer and sync resources for the + // given slot. + void freeBufferLocked(int slot); + + // freeAllBuffersLocked frees the GraphicBuffer and sync resources for + // all slots. + void freeAllBuffersLocked(); + + // stillTracking returns true iff the buffer item is still being tracked + // in one of the slots. + bool stillTracking(const BufferItem* item) const; + + // waitWhileAllocatingLocked blocks until mIsAllocating is false. + void waitWhileAllocatingLocked() const; + + // validateConsistencyLocked ensures that the free lists are in sync with + // the information stored in mSlots + void validateConsistencyLocked() const; + + // mAllocator is the connection to SurfaceFlinger that is used to allocate + // new GraphicBuffer objects. + sp mAllocator; + + // mMutex is the mutex used to prevent concurrent access to the member + // variables of BufferQueueCore objects. It must be locked whenever any + // member variable is accessed. + mutable Mutex mMutex; + + // mIsAbandoned indicates that the BufferQueue will no longer be used to + // consume image buffers pushed to it using the IGraphicBufferProducer + // interface. It is initialized to false, and set to true in the + // consumerDisconnect method. A BufferQueue that is abandoned will return + // the NO_INIT error from all IGraphicBufferProducer methods capable of + // returning an error. + bool mIsAbandoned; + + // mConsumerControlledByApp indicates whether the connected consumer is + // controlled by the application. + bool mConsumerControlledByApp; + + // mConsumerName is a string used to identify the BufferQueue in log + // messages. It is set by the IGraphicBufferConsumer::setConsumerName + // method. + String8 mConsumerName; + + // mConsumerListener is used to notify the connected consumer of + // asynchronous events that it may wish to react to. It is initially + // set to NULL and is written by consumerConnect and consumerDisconnect. + sp mConsumerListener; + + // mConsumerUsageBits contains flags that the consumer wants for + // GraphicBuffers. + uint32_t mConsumerUsageBits; + + // mConnectedApi indicates the producer API that is currently connected + // to this BufferQueue. It defaults to NO_CONNECTED_API, and gets updated + // by the connect and disconnect methods. + int mConnectedApi; + + // mConnectedProducerToken is used to set a binder death notification on + // the producer. + sp mConnectedProducerListener; + + // mSlots is an array of buffer slots that must be mirrored on the producer + // side. This allows buffer ownership to be transferred between the producer + // and consumer without sending a GraphicBuffer over Binder. The entire + // array is initialized to NULL at construction time, and buffers are + // allocated for a slot when requestBuffer is called with that slot's index. + BufferQueueDefs::SlotsType mSlots; + + // mQueue is a FIFO of queued buffers used in synchronous mode. + Fifo mQueue; + + // mFreeSlots contains all of the slots which are FREE and do not currently + // have a buffer attached + std::set mFreeSlots; + + // mFreeBuffers contains all of the slots which are FREE and currently have + // a buffer attached + std::list mFreeBuffers; + + // mOverrideMaxBufferCount is the limit on the number of buffers that will + // be allocated at one time. This value is set by the producer by calling + // setBufferCount. The default is 0, which means that the producer doesn't + // care about the number of buffers in the pool. In that case, + // mDefaultMaxBufferCount is used as the limit. + int mOverrideMaxBufferCount; + + // mDequeueCondition is a condition variable used for dequeueBuffer in + // synchronous mode. + mutable Condition mDequeueCondition; + + // mUseAsyncBuffer indicates whether an extra buffer is used in async mode + // to prevent dequeueBuffer from blocking. + bool mUseAsyncBuffer; + + // mDequeueBufferCannotBlock indicates whether dequeueBuffer is allowed to + // block. This flag is set during connect when both the producer and + // consumer are controlled by the application. + bool mDequeueBufferCannotBlock; + + // mDefaultBufferFormat can be set so it will override the buffer format + // when it isn't specified in dequeueBuffer. + PixelFormat mDefaultBufferFormat; + + // mDefaultWidth holds the default width of allocated buffers. It is used + // in dequeueBuffer if a width and height of 0 are specified. + uint32_t mDefaultWidth; + + // mDefaultHeight holds the default height of allocated buffers. It is used + // in dequeueBuffer if a width and height of 0 are specified. + uint32_t mDefaultHeight; + + // mDefaultBufferDataSpace holds the default dataSpace of queued buffers. + // It is used in queueBuffer if a dataspace of 0 (HAL_DATASPACE_UNKNOWN) + // is specified. + android_dataspace mDefaultBufferDataSpace; + + // mDefaultMaxBufferCount is the default limit on the number of buffers that + // will be allocated at one time. This default limit is set by the consumer. + // The limit (as opposed to the default limit) may be overriden by the + // producer. + int mDefaultMaxBufferCount; + + // mMaxAcquiredBufferCount is the number of buffers that the consumer may + // acquire at one time. It defaults to 1, and can be changed by the consumer + // via setMaxAcquiredBufferCount, but this may only be done while no + // producer is connected to the BufferQueue. This value is used to derive + // the value returned for the MIN_UNDEQUEUED_BUFFERS query to the producer. + int mMaxAcquiredBufferCount; + + // mBufferHasBeenQueued is true once a buffer has been queued. It is reset + // when something causes all buffers to be freed (e.g., changing the buffer + // count). + bool mBufferHasBeenQueued; + + // mFrameCounter is the free running counter, incremented on every + // successful queueBuffer call and buffer allocation. + uint64_t mFrameCounter; + + // mTransformHint is used to optimize for screen rotations. + uint32_t mTransformHint; + + // mSidebandStream is a handle to the sideband buffer stream, if any + sp mSidebandStream; + + // mIsAllocating indicates whether a producer is currently trying to allocate buffers (which + // releases mMutex while doing the allocation proper). Producers should not modify any of the + // FREE slots while this is true. mIsAllocatingCondition is signaled when this value changes to + // false. + bool mIsAllocating; + + // mIsAllocatingCondition is a condition variable used by producers to wait until mIsAllocating + // becomes false. + mutable Condition mIsAllocatingCondition; + + // mAllowAllocation determines whether dequeueBuffer is allowed to allocate + // new buffers + bool mAllowAllocation; + + // mBufferAge tracks the age of the contents of the most recently dequeued + // buffer as the number of frames that have elapsed since it was last queued + uint64_t mBufferAge; + + // mGenerationNumber stores the current generation number of the attached + // producer. Any attempt to attach a buffer with a different generation + // number will fail. + uint32_t mGenerationNumber; + +}; // class BufferQueueCore + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/BufferQueueDefs.h b/third_party/android_frameworks_native/include/gui/BufferQueueDefs.h new file mode 100644 index 00000000000000..83e95800378045 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferQueueDefs.h @@ -0,0 +1,35 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERQUEUECOREDEFS_H +#define ANDROID_GUI_BUFFERQUEUECOREDEFS_H + +#include + +namespace android { + class BufferQueueCore; + + namespace BufferQueueDefs { + // BufferQueue will keep track of at most this value of buffers. + // Attempts at runtime to increase the number of buffers past this + // will fail. + enum { NUM_BUFFER_SLOTS = 64 }; + + typedef BufferSlot SlotsType[NUM_BUFFER_SLOTS]; + } // namespace BufferQueueDefs +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/BufferQueueProducer.h b/third_party/android_frameworks_native/include/gui/BufferQueueProducer.h new file mode 100644 index 00000000000000..9754a89eacc29b --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferQueueProducer.h @@ -0,0 +1,228 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERQUEUEPRODUCER_H +#define ANDROID_GUI_BUFFERQUEUEPRODUCER_H + +#include +#include + +namespace android { + +class BufferSlot; + +class BufferQueueProducer : public BnGraphicBufferProducer, + private IBinder::DeathRecipient { +public: + friend class BufferQueue; // Needed to access binderDied + + BufferQueueProducer(const sp& core); + virtual ~BufferQueueProducer(); + + // requestBuffer returns the GraphicBuffer for slot N. + // + // In normal operation, this is called the first time slot N is returned + // by dequeueBuffer. It must be called again if dequeueBuffer returns + // flags indicating that previously-returned buffers are no longer valid. + virtual status_t requestBuffer(int slot, sp* buf); + + // setBufferCount updates the number of available buffer slots. If this + // method succeeds, buffer slots will be both unallocated and owned by + // the BufferQueue object (i.e. they are not owned by the producer or + // consumer). + // + // This will fail if the producer has dequeued any buffers, or if + // bufferCount is invalid. bufferCount must generally be a value + // between the minimum undequeued buffer count (exclusive) and NUM_BUFFER_SLOTS + // (inclusive). It may also be set to zero (the default) to indicate + // that the producer does not wish to set a value. The minimum value + // can be obtained by calling query(NATIVE_WINDOW_MIN_UNDEQUEUED_BUFFERS, + // ...). + // + // This may only be called by the producer. The consumer will be told + // to discard buffers through the onBuffersReleased callback. + virtual status_t setBufferCount(int bufferCount); + + // dequeueBuffer gets the next buffer slot index for the producer to use. + // If a buffer slot is available then that slot index is written to the + // location pointed to by the buf argument and a status of OK is returned. + // If no slot is available then a status of -EBUSY is returned and buf is + // unmodified. + // + // The outFence parameter will be updated to hold the fence associated with + // the buffer. The contents of the buffer must not be overwritten until the + // fence signals. If the fence is Fence::NO_FENCE, the buffer may be + // written immediately. + // + // The width and height parameters must be no greater than the minimum of + // GL_MAX_VIEWPORT_DIMS and GL_MAX_TEXTURE_SIZE (see: glGetIntegerv). + // An error due to invalid dimensions might not be reported until + // updateTexImage() is called. If width and height are both zero, the + // default values specified by setDefaultBufferSize() are used instead. + // + // If the format is 0, the default format will be used. + // + // The usage argument specifies gralloc buffer usage flags. The values + // are enumerated in gralloc.h, e.g. GRALLOC_USAGE_HW_RENDER. These + // will be merged with the usage flags specified by setConsumerUsageBits. + // + // The return value may be a negative error value or a non-negative + // collection of flags. If the flags are set, the return values are + // valid, but additional actions must be performed. + // + // If IGraphicBufferProducer::BUFFER_NEEDS_REALLOCATION is set, the + // producer must discard cached GraphicBuffer references for the slot + // returned in buf. + // If IGraphicBufferProducer::RELEASE_ALL_BUFFERS is set, the producer + // must discard cached GraphicBuffer references for all slots. + // + // In both cases, the producer will need to call requestBuffer to get a + // GraphicBuffer handle for the returned slot. + virtual status_t dequeueBuffer(int *outSlot, sp* outFence, + bool async, uint32_t width, uint32_t height, PixelFormat format, + uint32_t usage); + + // See IGraphicBufferProducer::detachBuffer + virtual status_t detachBuffer(int slot); + + // See IGraphicBufferProducer::detachNextBuffer + virtual status_t detachNextBuffer(sp* outBuffer, + sp* outFence); + + // See IGraphicBufferProducer::attachBuffer + virtual status_t attachBuffer(int* outSlot, const sp& buffer); + + // queueBuffer returns a filled buffer to the BufferQueue. + // + // Additional data is provided in the QueueBufferInput struct. Notably, + // a timestamp must be provided for the buffer. The timestamp is in + // nanoseconds, and must be monotonically increasing. Its other semantics + // (zero point, etc) are producer-specific and should be documented by the + // producer. + // + // The caller may provide a fence that signals when all rendering + // operations have completed. Alternatively, NO_FENCE may be used, + // indicating that the buffer is ready immediately. + // + // Some values are returned in the output struct: the current settings + // for default width and height, the current transform hint, and the + // number of queued buffers. + virtual status_t queueBuffer(int slot, + const QueueBufferInput& input, QueueBufferOutput* output); + + // cancelBuffer returns a dequeued buffer to the BufferQueue, but doesn't + // queue it for use by the consumer. + // + // The buffer will not be overwritten until the fence signals. The fence + // will usually be the one obtained from dequeueBuffer. + virtual void cancelBuffer(int slot, const sp& fence); + + // Query native window attributes. The "what" values are enumerated in + // window.h (e.g. NATIVE_WINDOW_FORMAT). + virtual int query(int what, int* outValue); + + // connect attempts to connect a producer API to the BufferQueue. This + // must be called before any other IGraphicBufferProducer methods are + // called except for getAllocator. A consumer must already be connected. + // + // This method will fail if connect was previously called on the + // BufferQueue and no corresponding disconnect call was made (i.e. if + // it's still connected to a producer). + // + // APIs are enumerated in window.h (e.g. NATIVE_WINDOW_API_CPU). + virtual status_t connect(const sp& listener, + int api, bool producerControlledByApp, QueueBufferOutput* output); + + // disconnect attempts to disconnect a producer API from the BufferQueue. + // Calling this method will cause any subsequent calls to other + // IGraphicBufferProducer methods to fail except for getAllocator and connect. + // Successfully calling connect after this will allow the other methods to + // succeed again. + // + // This method will fail if the the BufferQueue is not currently + // connected to the specified producer API. + virtual status_t disconnect(int api); + + // Attaches a sideband buffer stream to the IGraphicBufferProducer. + // + // A sideband stream is a device-specific mechanism for passing buffers + // from the producer to the consumer without using dequeueBuffer/ + // queueBuffer. If a sideband stream is present, the consumer can choose + // whether to acquire buffers from the sideband stream or from the queued + // buffers. + // + // Passing NULL or a different stream handle will detach the previous + // handle if any. + virtual status_t setSidebandStream(const sp& stream); + + // See IGraphicBufferProducer::allocateBuffers + virtual void allocateBuffers(bool async, uint32_t width, uint32_t height, + PixelFormat format, uint32_t usage); + + // See IGraphicBufferProducer::allowAllocation + virtual status_t allowAllocation(bool allow); + + // See IGraphicBufferProducer::setGenerationNumber + virtual status_t setGenerationNumber(uint32_t generationNumber); + + // See IGraphicBufferProducer::getConsumerName + virtual String8 getConsumerName() const override; + +private: + // This is required by the IBinder::DeathRecipient interface + virtual void binderDied(const wp& who); + + // waitForFreeSlotThenRelock finds the oldest slot in the FREE state. It may + // block if there are no available slots and we are not in non-blocking + // mode (producer and consumer controlled by the application). If it blocks, + // it will release mCore->mMutex while blocked so that other operations on + // the BufferQueue may succeed. + status_t waitForFreeSlotThenRelock(const char* caller, bool async, + int* found, status_t* returnFlags) const; + + sp mCore; + + // This references mCore->mSlots. Lock mCore->mMutex while accessing. + BufferQueueDefs::SlotsType& mSlots; + + // This is a cached copy of the name stored in the BufferQueueCore. + // It's updated during connect and dequeueBuffer (which should catch + // most updates). + String8 mConsumerName; + + uint32_t mStickyTransform; + + // This saves the fence from the last queueBuffer, such that the + // next queueBuffer call can throttle buffer production. The prior + // queueBuffer's fence is not nessessarily available elsewhere, + // since the previous buffer might have already been acquired. + sp mLastQueueBufferFence; + + // Take-a-ticket system for ensuring that onFrame* callbacks are called in + // the order that frames are queued. While the BufferQueue lock + // (mCore->mMutex) is held, a ticket is retained by the producer. After + // dropping the BufferQueue lock, the producer must wait on the condition + // variable until the current callback ticket matches its retained ticket. + Mutex mCallbackMutex; + int mNextCallbackTicket; // Protected by mCore->mMutex + int mCurrentCallbackTicket; // Protected by mCallbackMutex + Condition mCallbackCondition; + +}; // class BufferQueueProducer + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/BufferSlot.h b/third_party/android_frameworks_native/include/gui/BufferSlot.h new file mode 100644 index 00000000000000..6085e116a3d614 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/BufferSlot.h @@ -0,0 +1,142 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_BUFFERSLOT_H +#define ANDROID_GUI_BUFFERSLOT_H + +#include +#include + +#include +#include + +#include + +namespace android { + +class Fence; + +struct BufferSlot { + + BufferSlot() + : mEglDisplay(EGL_NO_DISPLAY), + mBufferState(BufferSlot::FREE), + mRequestBufferCalled(false), + mFrameNumber(0), + mEglFence(EGL_NO_SYNC_KHR), + mAcquireCalled(false), + mNeedsCleanupOnRelease(false), + mAttachedByConsumer(false) { + } + + // mGraphicBuffer points to the buffer allocated for this slot or is NULL + // if no buffer has been allocated. + sp mGraphicBuffer; + + // mEglDisplay is the EGLDisplay used to create EGLSyncKHR objects. + EGLDisplay mEglDisplay; + + // BufferState represents the different states in which a buffer slot + // can be. All slots are initially FREE. + enum BufferState { + // FREE indicates that the buffer is available to be dequeued + // by the producer. The buffer may be in use by the consumer for + // a finite time, so the buffer must not be modified until the + // associated fence is signaled. + // + // The slot is "owned" by BufferQueue. It transitions to DEQUEUED + // when dequeueBuffer is called. + FREE = 0, + + // DEQUEUED indicates that the buffer has been dequeued by the + // producer, but has not yet been queued or canceled. The + // producer may modify the buffer's contents as soon as the + // associated ready fence is signaled. + // + // The slot is "owned" by the producer. It can transition to + // QUEUED (via queueBuffer) or back to FREE (via cancelBuffer). + DEQUEUED = 1, + + // QUEUED indicates that the buffer has been filled by the + // producer and queued for use by the consumer. The buffer + // contents may continue to be modified for a finite time, so + // the contents must not be accessed until the associated fence + // is signaled. + // + // The slot is "owned" by BufferQueue. It can transition to + // ACQUIRED (via acquireBuffer) or to FREE (if another buffer is + // queued in asynchronous mode). + QUEUED = 2, + + // ACQUIRED indicates that the buffer has been acquired by the + // consumer. As with QUEUED, the contents must not be accessed + // by the consumer until the fence is signaled. + // + // The slot is "owned" by the consumer. It transitions to FREE + // when releaseBuffer is called. + ACQUIRED = 3 + }; + + static const char* bufferStateName(BufferState state); + + // mBufferState is the current state of this buffer slot. + BufferState mBufferState; + + // mRequestBufferCalled is used for validating that the producer did + // call requestBuffer() when told to do so. Technically this is not + // needed but useful for debugging and catching producer bugs. + bool mRequestBufferCalled; + + // mFrameNumber is the number of the queued frame for this slot. This + // is used to dequeue buffers in LRU order (useful because buffers + // may be released before their release fence is signaled). + uint64_t mFrameNumber; + + // mEglFence is the EGL sync object that must signal before the buffer + // associated with this buffer slot may be dequeued. It is initialized + // to EGL_NO_SYNC_KHR when the buffer is created and may be set to a + // new sync object in releaseBuffer. (This is deprecated in favor of + // mFence, below.) + EGLSyncKHR mEglFence; + + // mFence is a fence which will signal when work initiated by the + // previous owner of the buffer is finished. When the buffer is FREE, + // the fence indicates when the consumer has finished reading + // from the buffer, or when the producer has finished writing if it + // called cancelBuffer after queueing some writes. When the buffer is + // QUEUED, it indicates when the producer has finished filling the + // buffer. When the buffer is DEQUEUED or ACQUIRED, the fence has been + // passed to the consumer or producer along with ownership of the + // buffer, and mFence is set to NO_FENCE. + sp mFence; + + // Indicates whether this buffer has been seen by a consumer yet + bool mAcquireCalled; + + // Indicates whether this buffer needs to be cleaned up by the + // consumer. This is set when a buffer in ACQUIRED state is freed. + // It causes releaseBuffer to return STALE_BUFFER_SLOT. + bool mNeedsCleanupOnRelease; + + // Indicates whether the buffer was attached on the consumer side. + // If so, it needs to set the BUFFER_NEEDS_REALLOCATION flag when dequeued + // to prevent the producer from using a stale cached buffer. + bool mAttachedByConsumer; +}; + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/ConsumerBase.h b/third_party/android_frameworks_native/include/gui/ConsumerBase.h new file mode 100644 index 00000000000000..9307a26fb3a11a --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/ConsumerBase.h @@ -0,0 +1,252 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_CONSUMERBASE_H +#define ANDROID_GUI_CONSUMERBASE_H + +#include + +#include + +#include +#include +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class String8; + +// ConsumerBase is a base class for BufferQueue consumer end-points. It +// handles common tasks like management of the connection to the BufferQueue +// and the buffer pool. +class ConsumerBase : public virtual RefBase, + protected ConsumerListener { +public: + struct FrameAvailableListener : public virtual RefBase { + // See IConsumerListener::onFrame{Available,Replaced} + virtual void onFrameAvailable(const BufferItem& item) = 0; + virtual void onFrameReplaced(const BufferItem& /* item */) {} + }; + + virtual ~ConsumerBase(); + + // abandon frees all the buffers and puts the ConsumerBase into the + // 'abandoned' state. Once put in this state the ConsumerBase can never + // leave it. When in the 'abandoned' state, all methods of the + // IGraphicBufferProducer interface will fail with the NO_INIT error. + // + // Note that while calling this method causes all the buffers to be freed + // from the perspective of the the ConsumerBase, if there are additional + // references on the buffers (e.g. if a buffer is referenced by a client + // or by OpenGL ES as a texture) then those buffer will remain allocated. + void abandon(); + + // Returns true if the ConsumerBase is in the 'abandoned' state + bool isAbandoned(); + + // set the name of the ConsumerBase that will be used to identify it in + // log messages. + void setName(const String8& name); + + // dump writes the current state to a string. Child classes should add + // their state to the dump by overriding the dumpLocked method, which is + // called by these methods after locking the mutex. + void dump(String8& result) const; + void dump(String8& result, const char* prefix) const; + + // setFrameAvailableListener sets the listener object that will be notified + // when a new frame becomes available. + void setFrameAvailableListener(const wp& listener); + + // See IGraphicBufferConsumer::detachBuffer + status_t detachBuffer(int slot); + + // See IGraphicBufferConsumer::setDefaultBufferSize + status_t setDefaultBufferSize(uint32_t width, uint32_t height); + + // See IGraphicBufferConsumer::setDefaultBufferFormat + status_t setDefaultBufferFormat(PixelFormat defaultFormat); + + // See IGraphicBufferConsumer::setDefaultBufferDataSpace + status_t setDefaultBufferDataSpace(android_dataspace defaultDataSpace); + +private: + ConsumerBase(const ConsumerBase&); + void operator=(const ConsumerBase&); + +protected: + // ConsumerBase constructs a new ConsumerBase object to consume image + // buffers from the given IGraphicBufferConsumer. + // The controlledByApp flag indicates that this consumer is under the application's + // control. + ConsumerBase(const sp& consumer, bool controlledByApp = false); + + // onLastStrongRef gets called by RefBase just before the dtor of the most + // derived class. It is used to clean up the buffers so that ConsumerBase + // can coordinate the clean-up by calling into virtual methods implemented + // by the derived classes. This would not be possible from the + // ConsuemrBase dtor because by the time that gets called the derived + // classes have already been destructed. + // + // This methods should not need to be overridden by derived classes, but + // if they are overridden the ConsumerBase implementation must be called + // from the derived class. + virtual void onLastStrongRef(const void* id); + + // Implementation of the IConsumerListener interface. These + // calls are used to notify the ConsumerBase of asynchronous events in the + // BufferQueue. The onFrameAvailable, onFrameReplaced, and + // onBuffersReleased methods should not need to be overridden by derived + // classes, but if they are overridden the ConsumerBase implementation must + // be called from the derived class. The ConsumerBase version of + // onSidebandStreamChanged does nothing and can be overriden by derived + // classes if they want the notification. + virtual void onFrameAvailable(const BufferItem& item) override; + virtual void onFrameReplaced(const BufferItem& item) override; + virtual void onBuffersReleased() override; + virtual void onSidebandStreamChanged() override; + + // freeBufferLocked frees up the given buffer slot. If the slot has been + // initialized this will release the reference to the GraphicBuffer in that + // slot. Otherwise it has no effect. + // + // Derived classes should override this method to clean up any state they + // keep per slot. If it is overridden, the derived class's implementation + // must call ConsumerBase::freeBufferLocked. + // + // This method must be called with mMutex locked. + virtual void freeBufferLocked(int slotIndex); + + // abandonLocked puts the BufferQueue into the abandoned state, causing + // all future operations on it to fail. This method rather than the public + // abandon method should be overridden by child classes to add abandon- + // time behavior. + // + // Derived classes should override this method to clean up any object + // state they keep (as opposed to per-slot state). If it is overridden, + // the derived class's implementation must call ConsumerBase::abandonLocked. + // + // This method must be called with mMutex locked. + virtual void abandonLocked(); + + // dumpLocked dumps the current state of the ConsumerBase object to the + // result string. Each line is prefixed with the string pointed to by the + // prefix argument. The buffer argument points to a buffer that may be + // used for intermediate formatting data, and the size of that buffer is + // indicated by the size argument. + // + // Derived classes should override this method to dump their internal + // state. If this method is overridden the derived class's implementation + // should call ConsumerBase::dumpLocked. + // + // This method must be called with mMutex locked. + virtual void dumpLocked(String8& result, const char* prefix) const; + + // acquireBufferLocked fetches the next buffer from the BufferQueue and + // updates the buffer slot for the buffer returned. + // + // Derived classes should override this method to perform any + // initialization that must take place the first time a buffer is assigned + // to a slot. If it is overridden the derived class's implementation must + // call ConsumerBase::acquireBufferLocked. + virtual status_t acquireBufferLocked(BufferItem *item, nsecs_t presentWhen, + uint64_t maxFrameNumber = 0); + + // releaseBufferLocked relinquishes control over a buffer, returning that + // control to the BufferQueue. + // + // Derived classes should override this method to perform any cleanup that + // must take place when a buffer is released back to the BufferQueue. If + // it is overridden the derived class's implementation must call + // ConsumerBase::releaseBufferLocked.e + virtual status_t releaseBufferLocked(int slot, + const sp graphicBuffer, + EGLDisplay display, EGLSyncKHR eglFence); + + // returns true iff the slot still has the graphicBuffer in it. + bool stillTracking(int slot, const sp graphicBuffer); + + // addReleaseFence* adds the sync points associated with a fence to the set + // of sync points that must be reached before the buffer in the given slot + // may be used after the slot has been released. This should be called by + // derived classes each time some asynchronous work is kicked off that + // references the buffer. + status_t addReleaseFence(int slot, + const sp graphicBuffer, const sp& fence); + status_t addReleaseFenceLocked(int slot, + const sp graphicBuffer, const sp& fence); + + // Slot contains the information and object references that + // ConsumerBase maintains about a BufferQueue buffer slot. + struct Slot { + // mGraphicBuffer is the Gralloc buffer store in the slot or NULL if + // no Gralloc buffer is in the slot. + sp mGraphicBuffer; + + // mFence is a fence which will signal when the buffer associated with + // this buffer slot is no longer being used by the consumer and can be + // overwritten. The buffer can be dequeued before the fence signals; + // the producer is responsible for delaying writes until it signals. + sp mFence; + + // the frame number of the last acquired frame for this slot + uint64_t mFrameNumber; + }; + + // mSlots stores the buffers that have been allocated by the BufferQueue + // for each buffer slot. It is initialized to null pointers, and gets + // filled in with the result of BufferQueue::acquire when the + // client dequeues a buffer from a + // slot that has not yet been used. The buffer allocated to a slot will also + // be replaced if the requested buffer usage or geometry differs from that + // of the buffer allocated to a slot. + Slot mSlots[BufferQueue::NUM_BUFFER_SLOTS]; + + // mAbandoned indicates that the BufferQueue will no longer be used to + // consume images buffers pushed to it using the IGraphicBufferProducer + // interface. It is initialized to false, and set to true in the abandon + // method. A BufferQueue that has been abandoned will return the NO_INIT + // error from all IConsumerBase methods capable of returning an error. + bool mAbandoned; + + // mName is a string used to identify the ConsumerBase in log messages. + // It can be set by the setName method. + String8 mName; + + // mFrameAvailableListener is the listener object that will be called when a + // new frame becomes available. If it is not NULL it will be called from + // queueBuffer. + wp mFrameAvailableListener; + + // The ConsumerBase has-a BufferQueue and is responsible for creating this object + // if none is supplied + sp mConsumer; + + // mMutex is the mutex used to prevent concurrent access to the member + // variables of ConsumerBase objects. It must be locked whenever the + // member variables are accessed or when any of the *Locked methods are + // called. + // + // This mutex is intended to be locked by derived classes. + mutable Mutex mMutex; +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_CONSUMERBASE_H diff --git a/third_party/android_frameworks_native/include/gui/CpuConsumer.h b/third_party/android_frameworks_native/include/gui/CpuConsumer.h new file mode 100644 index 00000000000000..3b07a317501651 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/CpuConsumer.h @@ -0,0 +1,131 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_CPUCONSUMER_H +#define ANDROID_GUI_CPUCONSUMER_H + +#include + +#include + +#include +#include +#include + + +namespace android { + +class BufferQueue; + +/** + * CpuConsumer is a BufferQueue consumer endpoint that allows direct CPU + * access to the underlying gralloc buffers provided by BufferQueue. Multiple + * buffers may be acquired by it at once, to be used concurrently by the + * CpuConsumer owner. Sets gralloc usage flags to be software-read-only. + * This queue is synchronous by default. + */ + +class CpuConsumer : public ConsumerBase +{ + public: + typedef ConsumerBase::FrameAvailableListener FrameAvailableListener; + + struct LockedBuffer { + uint8_t *data; + uint32_t width; + uint32_t height; + PixelFormat format; + uint32_t stride; + Rect crop; + uint32_t transform; + uint32_t scalingMode; + int64_t timestamp; + android_dataspace dataSpace; + uint64_t frameNumber; + // this is the same as format, except for formats that are compatible with + // a flexible format (e.g. HAL_PIXEL_FORMAT_YCbCr_420_888). In the latter + // case this contains that flexible format + PixelFormat flexFormat; + // Values below are only valid when using HAL_PIXEL_FORMAT_YCbCr_420_888 + // or compatible format, in which case LockedBuffer::data + // contains the Y channel, and stride is the Y channel stride. For other + // formats, these will all be 0. + uint8_t *dataCb; + uint8_t *dataCr; + uint32_t chromaStride; + uint32_t chromaStep; + }; + + // Create a new CPU consumer. The maxLockedBuffers parameter specifies + // how many buffers can be locked for user access at the same time. + CpuConsumer(const sp& bq, + size_t maxLockedBuffers, bool controlledByApp = false); + + virtual ~CpuConsumer(); + + // set the name of the CpuConsumer that will be used to identify it in + // log messages. + void setName(const String8& name); + + // Gets the next graphics buffer from the producer and locks it for CPU use, + // filling out the passed-in locked buffer structure with the native pointer + // and metadata. Returns BAD_VALUE if no new buffer is available, and + // NOT_ENOUGH_DATA if the maximum number of buffers is already locked. + // + // Only a fixed number of buffers can be locked at a time, determined by the + // construction-time maxLockedBuffers parameter. If INVALID_OPERATION is + // returned by lockNextBuffer, then old buffers must be returned to the queue + // by calling unlockBuffer before more buffers can be acquired. + status_t lockNextBuffer(LockedBuffer *nativeBuffer); + + // Returns a locked buffer to the queue, allowing it to be reused. Since + // only a fixed number of buffers may be locked at a time, old buffers must + // be released by calling unlockBuffer to ensure new buffers can be acquired by + // lockNextBuffer. + status_t unlockBuffer(const LockedBuffer &nativeBuffer); + + private: + // Maximum number of buffers that can be locked at a time + size_t mMaxLockedBuffers; + + status_t releaseAcquiredBufferLocked(size_t lockedIdx); + + virtual void freeBufferLocked(int slotIndex); + + // Tracking for buffers acquired by the user + struct AcquiredBuffer { + // Need to track the original mSlot index and the buffer itself because + // the mSlot entry may be freed/reused before the acquired buffer is + // released. + int mSlot; + sp mGraphicBuffer; + void *mBufferPointer; + + AcquiredBuffer() : + mSlot(BufferQueue::INVALID_BUFFER_SLOT), + mBufferPointer(NULL) { + } + }; + Vector mAcquiredBuffers; + + // Count of currently locked buffers + size_t mCurrentLockedBuffers; + +}; + +} // namespace android + +#endif // ANDROID_GUI_CPUCONSUMER_H diff --git a/third_party/android_frameworks_native/include/gui/DisplayEventReceiver.h b/third_party/android_frameworks_native/include/gui/DisplayEventReceiver.h new file mode 100644 index 00000000000000..a4718b91c6e6b8 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/DisplayEventReceiver.h @@ -0,0 +1,137 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_DISPLAY_EVENT_H +#define ANDROID_GUI_DISPLAY_EVENT_H + +#include +#include + +#include +#include +#include + +#include + +// ---------------------------------------------------------------------------- + +namespace android { + +// ---------------------------------------------------------------------------- + +class BitTube; +class IDisplayEventConnection; + +// ---------------------------------------------------------------------------- + +class DisplayEventReceiver { +public: + enum { + DISPLAY_EVENT_VSYNC = 'vsyn', + DISPLAY_EVENT_HOTPLUG = 'plug' + }; + + struct Event { + + struct Header { + uint32_t type; + uint32_t id; + nsecs_t timestamp __attribute__((aligned(8))); + }; + + struct VSync { + uint32_t count; + }; + + struct Hotplug { + bool connected; + }; + + Header header; + union { + VSync vsync; + Hotplug hotplug; + }; + }; + +public: + /* + * DisplayEventReceiver creates and registers an event connection with + * SurfaceFlinger. VSync events are disabled by default. Call setVSyncRate + * or requestNextVsync to receive them. + * Other events start being delivered immediately. + */ + DisplayEventReceiver(); + + /* + * ~DisplayEventReceiver severs the connection with SurfaceFlinger, new events + * stop being delivered immediately. Note that the queue could have + * some events pending. These will be delivered. + */ + ~DisplayEventReceiver(); + + /* + * initCheck returns the state of DisplayEventReceiver after construction. + */ + status_t initCheck() const; + + /* + * getFd returns the file descriptor to use to receive events. + * OWNERSHIP IS RETAINED by DisplayEventReceiver. DO NOT CLOSE this + * file-descriptor. + */ + int getFd() const; + + /* + * getEvents reads events from the queue and returns how many events were + * read. Returns 0 if there are no more events or a negative error code. + * If NOT_ENOUGH_DATA is returned, the object has become invalid forever, it + * should be destroyed and getEvents() shouldn't be called again. + */ + ssize_t getEvents(Event* events, size_t count); + static ssize_t getEvents(const sp& dataChannel, + Event* events, size_t count); + + /* + * sendEvents write events to the queue and returns how many events were + * written. + */ + static ssize_t sendEvents(const sp& dataChannel, + Event const* events, size_t count); + + /* + * setVsyncRate() sets the Event::VSync delivery rate. A value of + * 1 returns every Event::VSync. A value of 2 returns every other event, + * etc... a value of 0 returns no event unless requestNextVsync() has + * been called. + */ + status_t setVsyncRate(uint32_t count); + + /* + * requestNextVsync() schedules the next Event::VSync. It has no effect + * if the vsync rate is > 0. + */ + status_t requestNextVsync(); + +private: + sp mEventConnection; + sp mDataChannel; +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_DISPLAY_EVENT_H diff --git a/third_party/android_frameworks_native/include/gui/GLConsumer.h b/third_party/android_frameworks_native/include/gui/GLConsumer.h new file mode 100644 index 00000000000000..c35c7be064224e --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/GLConsumer.h @@ -0,0 +1,488 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_CONSUMER_H +#define ANDROID_GUI_CONSUMER_H + +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + + +class String8; + +/* + * GLConsumer consumes buffers of graphics data from a BufferQueue, + * and makes them available to OpenGL as a texture. + * + * A typical usage pattern is to set up the GLConsumer with the + * desired options, and call updateTexImage() when a new frame is desired. + * If a new frame is available, the texture will be updated. If not, + * the previous contents are retained. + * + * By default, the texture is attached to the GL_TEXTURE_EXTERNAL_OES + * texture target, in the EGL context of the first thread that calls + * updateTexImage(). + * + * This class was previously called SurfaceTexture. + */ +class GLConsumer : public ConsumerBase { +public: + enum { TEXTURE_EXTERNAL = 0x8D65 }; // GL_TEXTURE_EXTERNAL_OES + typedef ConsumerBase::FrameAvailableListener FrameAvailableListener; + + // GLConsumer constructs a new GLConsumer object. If the constructor with + // the tex parameter is used, tex indicates the name of the OpenGL ES + // texture to which images are to be streamed. texTarget specifies the + // OpenGL ES texture target to which the texture will be bound in + // updateTexImage. useFenceSync specifies whether fences should be used to + // synchronize access to buffers if that behavior is enabled at + // compile-time. + // + // A GLConsumer may be detached from one OpenGL ES context and then + // attached to a different context using the detachFromContext and + // attachToContext methods, respectively. The intention of these methods is + // purely to allow a GLConsumer to be transferred from one consumer + // context to another. If such a transfer is not needed there is no + // requirement that either of these methods be called. + // + // If the constructor with the tex parameter is used, the GLConsumer is + // created in a state where it is considered attached to an OpenGL ES + // context for the purposes of the attachToContext and detachFromContext + // methods. However, despite being considered "attached" to a context, the + // specific OpenGL ES context doesn't get latched until the first call to + // updateTexImage. After that point, all calls to updateTexImage must be + // made with the same OpenGL ES context current. + // + // If the constructor without the tex parameter is used, the GLConsumer is + // created in a detached state, and attachToContext must be called before + // calls to updateTexImage. + GLConsumer(const sp& bq, + uint32_t tex, uint32_t texureTarget, bool useFenceSync, + bool isControlledByApp); + + GLConsumer(const sp& bq, uint32_t texureTarget, + bool useFenceSync, bool isControlledByApp); + + // updateTexImage acquires the most recently queued buffer, and sets the + // image contents of the target texture to it. + // + // This call may only be made while the OpenGL ES context to which the + // target texture belongs is bound to the calling thread. + // + // This calls doGLFenceWait to ensure proper synchronization. + status_t updateTexImage(); + + // releaseTexImage releases the texture acquired in updateTexImage(). + // This is intended to be used in single buffer mode. + // + // This call may only be made while the OpenGL ES context to which the + // target texture belongs is bound to the calling thread. + status_t releaseTexImage(); + + // setReleaseFence stores a fence that will signal when the current buffer + // is no longer being read. This fence will be returned to the producer + // when the current buffer is released by updateTexImage(). Multiple + // fences can be set for a given buffer; they will be merged into a single + // union fence. + void setReleaseFence(const sp& fence); + + // setDefaultMaxBufferCount sets the default limit on the maximum number + // of buffers that will be allocated at one time. The image producer may + // override the limit. + status_t setDefaultMaxBufferCount(int bufferCount); + + // getTransformMatrix retrieves the 4x4 texture coordinate transform matrix + // associated with the texture image set by the most recent call to + // updateTexImage. + // + // This transform matrix maps 2D homogeneous texture coordinates of the form + // (s, t, 0, 1) with s and t in the inclusive range [0, 1] to the texture + // coordinate that should be used to sample that location from the texture. + // Sampling the texture outside of the range of this transform is undefined. + // + // This transform is necessary to compensate for transforms that the stream + // content producer may implicitly apply to the content. By forcing users of + // a GLConsumer to apply this transform we avoid performing an extra + // copy of the data that would be needed to hide the transform from the + // user. + // + // The matrix is stored in column-major order so that it may be passed + // directly to OpenGL ES via the glLoadMatrixf or glUniformMatrix4fv + // functions. + void getTransformMatrix(float mtx[16]); + + // getTimestamp retrieves the timestamp associated with the texture image + // set by the most recent call to updateTexImage. + // + // The timestamp is in nanoseconds, and is monotonically increasing. Its + // other semantics (zero point, etc) are source-dependent and should be + // documented by the source. + int64_t getTimestamp(); + + // getFrameNumber retrieves the frame number associated with the texture + // image set by the most recent call to updateTexImage. + // + // The frame number is an incrementing counter set to 0 at the creation of + // the BufferQueue associated with this consumer. + uint64_t getFrameNumber(); + + // setDefaultBufferSize is used to set the size of buffers returned by + // requestBuffers when a with and height of zero is requested. + // A call to setDefaultBufferSize() may trigger requestBuffers() to + // be called from the client. + // The width and height parameters must be no greater than the minimum of + // GL_MAX_VIEWPORT_DIMS and GL_MAX_TEXTURE_SIZE (see: glGetIntegerv). + // An error due to invalid dimensions might not be reported until + // updateTexImage() is called. + status_t setDefaultBufferSize(uint32_t width, uint32_t height); + + // setFilteringEnabled sets whether the transform matrix should be computed + // for use with bilinear filtering. + void setFilteringEnabled(bool enabled); + + // getCurrentBuffer returns the buffer associated with the current image. + sp getCurrentBuffer() const; + + // getCurrentTextureTarget returns the texture target of the current + // texture as returned by updateTexImage(). + uint32_t getCurrentTextureTarget() const; + + // getCurrentCrop returns the cropping rectangle of the current buffer. + Rect getCurrentCrop() const; + + // getCurrentTransform returns the transform of the current buffer. + uint32_t getCurrentTransform() const; + + // getCurrentScalingMode returns the scaling mode of the current buffer. + uint32_t getCurrentScalingMode() const; + + // getCurrentFence returns the fence indicating when the current buffer is + // ready to be read from. + sp getCurrentFence() const; + + // doGLFenceWait inserts a wait command into the OpenGL ES command stream + // to ensure that it is safe for future OpenGL ES commands to access the + // current texture buffer. + status_t doGLFenceWait() const; + + // set the name of the GLConsumer that will be used to identify it in + // log messages. + void setName(const String8& name); + + // These functions call the corresponding BufferQueue implementation + // so the refactoring can proceed smoothly + status_t setDefaultBufferFormat(PixelFormat defaultFormat); + status_t setDefaultBufferDataSpace(android_dataspace defaultDataSpace); + status_t setConsumerUsageBits(uint32_t usage); + status_t setTransformHint(uint32_t hint); + + // detachFromContext detaches the GLConsumer from the calling thread's + // current OpenGL ES context. This context must be the same as the context + // that was current for previous calls to updateTexImage. + // + // Detaching a GLConsumer from an OpenGL ES context will result in the + // deletion of the OpenGL ES texture object into which the images were being + // streamed. After a GLConsumer has been detached from the OpenGL ES + // context calls to updateTexImage will fail returning INVALID_OPERATION + // until the GLConsumer is attached to a new OpenGL ES context using the + // attachToContext method. + status_t detachFromContext(); + + // attachToContext attaches a GLConsumer that is currently in the + // 'detached' state to the current OpenGL ES context. A GLConsumer is + // in the 'detached' state iff detachFromContext has successfully been + // called and no calls to attachToContext have succeeded since the last + // detachFromContext call. Calls to attachToContext made on a + // GLConsumer that is not in the 'detached' state will result in an + // INVALID_OPERATION error. + // + // The tex argument specifies the OpenGL ES texture object name in the + // new context into which the image contents will be streamed. A successful + // call to attachToContext will result in this texture object being bound to + // the texture target and populated with the image contents that were + // current at the time of the last call to detachFromContext. + status_t attachToContext(uint32_t tex); + +protected: + + // abandonLocked overrides the ConsumerBase method to clear + // mCurrentTextureImage in addition to the ConsumerBase behavior. + virtual void abandonLocked(); + + // dumpLocked overrides the ConsumerBase method to dump GLConsumer- + // specific info in addition to the ConsumerBase behavior. + virtual void dumpLocked(String8& result, const char* prefix) const; + + // acquireBufferLocked overrides the ConsumerBase method to update the + // mEglSlots array in addition to the ConsumerBase behavior. + virtual status_t acquireBufferLocked(BufferItem *item, nsecs_t presentWhen, + uint64_t maxFrameNumber = 0) override; + + // releaseBufferLocked overrides the ConsumerBase method to update the + // mEglSlots array in addition to the ConsumerBase. + virtual status_t releaseBufferLocked(int slot, + const sp graphicBuffer, + EGLDisplay display, EGLSyncKHR eglFence); + + status_t releaseBufferLocked(int slot, + const sp graphicBuffer, EGLSyncKHR eglFence) { + return releaseBufferLocked(slot, graphicBuffer, mEglDisplay, eglFence); + } + + static bool isExternalFormat(PixelFormat format); + + // This releases the buffer in the slot referenced by mCurrentTexture, + // then updates state to refer to the BufferItem, which must be a + // newly-acquired buffer. + status_t updateAndReleaseLocked(const BufferItem& item); + + // Binds mTexName and the current buffer to mTexTarget. Uses + // mCurrentTexture if it's set, mCurrentTextureImage if not. If the + // bind succeeds, this calls doGLFenceWait. + status_t bindTextureImageLocked(); + + // Gets the current EGLDisplay and EGLContext values, and compares them + // to mEglDisplay and mEglContext. If the fields have been previously + // set, the values must match; if not, the fields are set to the current + // values. + // The contextCheck argument is used to ensure that a GL context is + // properly set; when set to false, the check is not performed. + status_t checkAndUpdateEglStateLocked(bool contextCheck = false); + +private: + // EglImage is a utility class for tracking and creating EGLImageKHRs. There + // is primarily just one image per slot, but there is also special cases: + // - For releaseTexImage, we use a debug image (mReleasedTexImage) + // - After freeBuffer, we must still keep the current image/buffer + // Reference counting EGLImages lets us handle all these cases easily while + // also only creating new EGLImages from buffers when required. + class EglImage : public LightRefBase { + public: + EglImage(sp graphicBuffer); + + // createIfNeeded creates an EGLImage if required (we haven't created + // one yet, or the EGLDisplay or crop-rect has changed). + status_t createIfNeeded(EGLDisplay display, + const Rect& cropRect, + bool forceCreate = false); + + // This calls glEGLImageTargetTexture2DOES to bind the image to the + // texture in the specified texture target. + void bindToTextureTarget(uint32_t texTarget); + + const sp& graphicBuffer() { return mGraphicBuffer; } + const native_handle* graphicBufferHandle() { + return mGraphicBuffer == NULL ? NULL : mGraphicBuffer->handle; + } + + private: + // Only allow instantiation using ref counting. + friend class LightRefBase; + virtual ~EglImage(); + + // createImage creates a new EGLImage from a GraphicBuffer. + EGLImageKHR createImage(EGLDisplay dpy, + const sp& graphicBuffer, const Rect& crop); + + // Disallow copying + EglImage(const EglImage& rhs); + void operator = (const EglImage& rhs); + + // mGraphicBuffer is the buffer that was used to create this image. + sp mGraphicBuffer; + + // mEglImage is the EGLImage created from mGraphicBuffer. + EGLImageKHR mEglImage; + + // mEGLDisplay is the EGLDisplay that was used to create mEglImage. + EGLDisplay mEglDisplay; + + // mCropRect is the crop rectangle passed to EGL when mEglImage + // was created. + Rect mCropRect; + }; + + // freeBufferLocked frees up the given buffer slot. If the slot has been + // initialized this will release the reference to the GraphicBuffer in that + // slot and destroy the EGLImage in that slot. Otherwise it has no effect. + // + // This method must be called with mMutex locked. + virtual void freeBufferLocked(int slotIndex); + + // computeCurrentTransformMatrixLocked computes the transform matrix for the + // current texture. It uses mCurrentTransform and the current GraphicBuffer + // to compute this matrix and stores it in mCurrentTransformMatrix. + // mCurrentTextureImage must not be NULL. + void computeCurrentTransformMatrixLocked(); + + // doGLFenceWaitLocked inserts a wait command into the OpenGL ES command + // stream to ensure that it is safe for future OpenGL ES commands to + // access the current texture buffer. + status_t doGLFenceWaitLocked() const; + + // syncForReleaseLocked performs the synchronization needed to release the + // current slot from an OpenGL ES context. If needed it will set the + // current slot's fence to guard against a producer accessing the buffer + // before the outstanding accesses have completed. + status_t syncForReleaseLocked(EGLDisplay dpy); + + // returns a graphic buffer used when the texture image has been released + static sp getDebugTexImageBuffer(); + + // The default consumer usage flags that GLConsumer always sets on its + // BufferQueue instance; these will be OR:d with any additional flags passed + // from the GLConsumer user. In particular, GLConsumer will always + // consume buffers as hardware textures. + static const uint32_t DEFAULT_USAGE_FLAGS = GraphicBuffer::USAGE_HW_TEXTURE; + + // mCurrentTextureImage is the EglImage/buffer of the current texture. It's + // possible that this buffer is not associated with any buffer slot, so we + // must track it separately in order to support the getCurrentBuffer method. + sp mCurrentTextureImage; + + // mCurrentCrop is the crop rectangle that applies to the current texture. + // It gets set each time updateTexImage is called. + Rect mCurrentCrop; + + // mCurrentTransform is the transform identifier for the current texture. It + // gets set each time updateTexImage is called. + uint32_t mCurrentTransform; + + // mCurrentScalingMode is the scaling mode for the current texture. It gets + // set each time updateTexImage is called. + uint32_t mCurrentScalingMode; + + // mCurrentFence is the fence received from BufferQueue in updateTexImage. + sp mCurrentFence; + + // mCurrentTransformMatrix is the transform matrix for the current texture. + // It gets computed by computeTransformMatrix each time updateTexImage is + // called. + float mCurrentTransformMatrix[16]; + + // mCurrentTimestamp is the timestamp for the current texture. It + // gets set each time updateTexImage is called. + int64_t mCurrentTimestamp; + + // mCurrentFrameNumber is the frame counter for the current texture. + // It gets set each time updateTexImage is called. + uint64_t mCurrentFrameNumber; + + uint32_t mDefaultWidth, mDefaultHeight; + + // mFilteringEnabled indicates whether the transform matrix is computed for + // use with bilinear filtering. It defaults to true and is changed by + // setFilteringEnabled(). + bool mFilteringEnabled; + + // mTexName is the name of the OpenGL texture to which streamed images will + // be bound when updateTexImage is called. It is set at construction time + // and can be changed with a call to attachToContext. + uint32_t mTexName; + + // mUseFenceSync indicates whether creation of the EGL_KHR_fence_sync + // extension should be used to prevent buffers from being dequeued before + // it's safe for them to be written. It gets set at construction time and + // never changes. + const bool mUseFenceSync; + + // mTexTarget is the GL texture target with which the GL texture object is + // associated. It is set in the constructor and never changed. It is + // almost always GL_TEXTURE_EXTERNAL_OES except for one use case in Android + // Browser. In that case it is set to GL_TEXTURE_2D to allow + // glCopyTexSubImage to read from the texture. This is a hack to work + // around a GL driver limitation on the number of FBO attachments, which the + // browser's tile cache exceeds. + const uint32_t mTexTarget; + + // EGLSlot contains the information and object references that + // GLConsumer maintains about a BufferQueue buffer slot. + struct EglSlot { + EglSlot() : mEglFence(EGL_NO_SYNC_KHR) {} + + // mEglImage is the EGLImage created from mGraphicBuffer. + sp mEglImage; + + // mFence is the EGL sync object that must signal before the buffer + // associated with this buffer slot may be dequeued. It is initialized + // to EGL_NO_SYNC_KHR when the buffer is created and (optionally, based + // on a compile-time option) set to a new sync object in updateTexImage. + EGLSyncKHR mEglFence; + }; + + // mEglDisplay is the EGLDisplay with which this GLConsumer is currently + // associated. It is intialized to EGL_NO_DISPLAY and gets set to the + // current display when updateTexImage is called for the first time and when + // attachToContext is called. + EGLDisplay mEglDisplay; + + // mEglContext is the OpenGL ES context with which this GLConsumer is + // currently associated. It is initialized to EGL_NO_CONTEXT and gets set + // to the current GL context when updateTexImage is called for the first + // time and when attachToContext is called. + EGLContext mEglContext; + + // mEGLSlots stores the buffers that have been allocated by the BufferQueue + // for each buffer slot. It is initialized to null pointers, and gets + // filled in with the result of BufferQueue::acquire when the + // client dequeues a buffer from a + // slot that has not yet been used. The buffer allocated to a slot will also + // be replaced if the requested buffer usage or geometry differs from that + // of the buffer allocated to a slot. + EglSlot mEglSlots[BufferQueue::NUM_BUFFER_SLOTS]; + + // mCurrentTexture is the buffer slot index of the buffer that is currently + // bound to the OpenGL texture. It is initialized to INVALID_BUFFER_SLOT, + // indicating that no buffer slot is currently bound to the texture. Note, + // however, that a value of INVALID_BUFFER_SLOT does not necessarily mean + // that no buffer is bound to the texture. A call to setBufferCount will + // reset mCurrentTexture to INVALID_BUFFER_SLOT. + int mCurrentTexture; + + // mAttached indicates whether the ConsumerBase is currently attached to + // an OpenGL ES context. For legacy reasons, this is initialized to true, + // indicating that the ConsumerBase is considered to be attached to + // whatever context is current at the time of the first updateTexImage call. + // It is set to false by detachFromContext, and then set to true again by + // attachToContext. + bool mAttached; + + // protects static initialization + static Mutex sStaticInitLock; + + // mReleasedTexImageBuffer is a dummy buffer used when in single buffer + // mode and releaseTexImage() has been called + static sp sReleasedTexImageBuffer; + sp mReleasedTexImage; +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_CONSUMER_H diff --git a/third_party/android_frameworks_native/include/gui/GraphicBufferAlloc.h b/third_party/android_frameworks_native/include/gui/GraphicBufferAlloc.h new file mode 100644 index 00000000000000..69fe51ef932061 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/GraphicBufferAlloc.h @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_SF_GRAPHIC_BUFFER_ALLOC_H +#define ANDROID_SF_GRAPHIC_BUFFER_ALLOC_H + +#include +#include + +#include +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +class GraphicBuffer; + +class GraphicBufferAlloc : public BnGraphicBufferAlloc { +public: + GraphicBufferAlloc(); + virtual ~GraphicBufferAlloc(); + virtual sp createGraphicBuffer(uint32_t width, + uint32_t height, PixelFormat format, uint32_t usage, + status_t* error); +}; + + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_SF_GRAPHIC_BUFFER_ALLOC_H diff --git a/third_party/android_frameworks_native/include/gui/GuiConfig.h b/third_party/android_frameworks_native/include/gui/GuiConfig.h new file mode 100644 index 00000000000000..b020ed9b6a3d13 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/GuiConfig.h @@ -0,0 +1,29 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_CONFIG_H +#define ANDROID_GUI_CONFIG_H + +#include + +namespace android { + +// Append the libgui configuration details to configStr. +void appendGuiConfigString(String8& configStr); + +}; // namespace android + +#endif /*ANDROID_GUI_CONFIG_H*/ diff --git a/third_party/android_frameworks_native/include/gui/IConsumerListener.h b/third_party/android_frameworks_native/include/gui/IConsumerListener.h new file mode 100644 index 00000000000000..3f3979956470f6 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IConsumerListener.h @@ -0,0 +1,104 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_ICONSUMERLISTENER_H +#define ANDROID_GUI_ICONSUMERLISTENER_H + +#include +#include + +#include +#include + +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class BufferItem; + +// ConsumerListener is the interface through which the BufferQueue notifies +// the consumer of events that the consumer may wish to react to. Because +// the consumer will generally have a mutex that is locked during calls from +// the consumer to the BufferQueue, these calls from the BufferQueue to the +// consumer *MUST* be called only when the BufferQueue mutex is NOT locked. + +class ConsumerListener : public virtual RefBase { +public: + ConsumerListener() { } + virtual ~ConsumerListener() { } + + // onFrameAvailable is called from queueBuffer each time an additional + // frame becomes available for consumption. This means that frames that + // are queued while in asynchronous mode only trigger the callback if no + // previous frames are pending. Frames queued while in synchronous mode + // always trigger the callback. The item passed to the callback will contain + // all of the information about the queued frame except for its + // GraphicBuffer pointer, which will always be null. + // + // This is called without any lock held and can be called concurrently + // by multiple threads. + virtual void onFrameAvailable(const BufferItem& item) = 0; /* Asynchronous */ + + // onFrameReplaced is called from queueBuffer if the frame being queued is + // replacing an existing slot in the queue. Any call to queueBuffer that + // doesn't call onFrameAvailable will call this callback instead. The item + // passed to the callback will contain all of the information about the + // queued frame except for its GraphicBuffer pointer, which will always be + // null. + // + // This is called without any lock held and can be called concurrently + // by multiple threads. + virtual void onFrameReplaced(const BufferItem& /* item */) {} /* Asynchronous */ + + // onBuffersReleased is called to notify the buffer consumer that the + // BufferQueue has released its references to one or more GraphicBuffers + // contained in its slots. The buffer consumer should then call + // BufferQueue::getReleasedBuffers to retrieve the list of buffers + // + // This is called without any lock held and can be called concurrently + // by multiple threads. + virtual void onBuffersReleased() = 0; /* Asynchronous */ + + // onSidebandStreamChanged is called to notify the buffer consumer that the + // BufferQueue's sideband buffer stream has changed. This is called when a + // stream is first attached and when it is either detached or replaced by a + // different stream. + virtual void onSidebandStreamChanged() = 0; /* Asynchronous */ +}; + + +class IConsumerListener : public ConsumerListener, public IInterface +{ +public: + DECLARE_META_INTERFACE(ConsumerListener); +}; + +// ---------------------------------------------------------------------------- + +class BnConsumerListener : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_ICONSUMERLISTENER_H diff --git a/third_party/android_frameworks_native/include/gui/IDisplayEventConnection.h b/third_party/android_frameworks_native/include/gui/IDisplayEventConnection.h new file mode 100644 index 00000000000000..86247de62bb0ed --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IDisplayEventConnection.h @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_IDISPLAY_EVENT_CONNECTION_H +#define ANDROID_GUI_IDISPLAY_EVENT_CONNECTION_H + +#include +#include + +#include +#include + +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class BitTube; + +class IDisplayEventConnection : public IInterface +{ +public: + + DECLARE_META_INTERFACE(DisplayEventConnection); + + /* + * getDataChannel() returns a BitTube where to receive the events from + */ + virtual sp getDataChannel() const = 0; + + /* + * setVsyncRate() sets the vsync event delivery rate. A value of + * 1 returns every vsync events. A value of 2 returns every other events, + * etc... a value of 0 returns no event unless requestNextVsync() has + * been called. + */ + virtual void setVsyncRate(uint32_t count) = 0; + + /* + * requestNextVsync() schedules the next vsync event. It has no effect + * if the vsync rate is > 0. + */ + virtual void requestNextVsync() = 0; // asynchronous +}; + +// ---------------------------------------------------------------------------- + +class BnDisplayEventConnection : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_IDISPLAY_EVENT_CONNECTION_H diff --git a/third_party/android_frameworks_native/include/gui/IGraphicBufferAlloc.h b/third_party/android_frameworks_native/include/gui/IGraphicBufferAlloc.h new file mode 100644 index 00000000000000..f3c46ec2edfa9d --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IGraphicBufferAlloc.h @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_IGRAPHIC_BUFFER_ALLOC_H +#define ANDROID_GUI_IGRAPHIC_BUFFER_ALLOC_H + +#include +#include + +#include +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class GraphicBuffer; + +class IGraphicBufferAlloc : public IInterface +{ +public: + DECLARE_META_INTERFACE(GraphicBufferAlloc); + + /* Create a new GraphicBuffer for the client to use. + */ + virtual sp createGraphicBuffer(uint32_t w, uint32_t h, + PixelFormat format, uint32_t usage, status_t* error) = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnGraphicBufferAlloc : public BnInterface +{ +public: + virtual status_t onTransact(uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_GUI_IGRAPHIC_BUFFER_ALLOC_H diff --git a/third_party/android_frameworks_native/include/gui/IGraphicBufferConsumer.h b/third_party/android_frameworks_native/include/gui/IGraphicBufferConsumer.h new file mode 100644 index 00000000000000..60ec9cc0e91936 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IGraphicBufferConsumer.h @@ -0,0 +1,280 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_IGRAPHICBUFFERCONSUMER_H +#define ANDROID_GUI_IGRAPHICBUFFERCONSUMER_H + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class BufferItem; +class Fence; +class GraphicBuffer; +class IConsumerListener; +class NativeHandle; + +class IGraphicBufferConsumer : public IInterface { + +public: + enum { + // Returned by releaseBuffer, after which the consumer must + // free any references to the just-released buffer that it might have. + STALE_BUFFER_SLOT = 1, + // Returned by dequeueBuffer if there are no pending buffers available. + NO_BUFFER_AVAILABLE, + // Returned by dequeueBuffer if it's too early for the buffer to be acquired. + PRESENT_LATER, + }; + + // acquireBuffer attempts to acquire ownership of the next pending buffer in + // the BufferQueue. If no buffer is pending then it returns + // NO_BUFFER_AVAILABLE. If a buffer is successfully acquired, the + // information about the buffer is returned in BufferItem. + // + // If the buffer returned had previously been + // acquired then the BufferItem::mGraphicBuffer field of buffer is set to + // NULL and it is assumed that the consumer still holds a reference to the + // buffer. + // + // If presentWhen is non-zero, it indicates the time when the buffer will + // be displayed on screen. If the buffer's timestamp is farther in the + // future, the buffer won't be acquired, and PRESENT_LATER will be + // returned. The presentation time is in nanoseconds, and the time base + // is CLOCK_MONOTONIC. + // + // If maxFrameNumber is non-zero, it indicates that acquireBuffer should + // only return a buffer with a frame number less than or equal to + // maxFrameNumber. If no such frame is available (such as when a buffer has + // been replaced but the consumer has not received the onFrameReplaced + // callback), then PRESENT_LATER will be returned. + // + // Return of NO_ERROR means the operation completed as normal. + // + // Return of a positive value means the operation could not be completed + // at this time, but the user should try again later: + // * NO_BUFFER_AVAILABLE - no buffer is pending (nothing queued by producer) + // * PRESENT_LATER - the buffer's timestamp is farther in the future + // + // Return of a negative value means an error has occurred: + // * INVALID_OPERATION - too many buffers have been acquired + virtual status_t acquireBuffer(BufferItem* buffer, nsecs_t presentWhen, + uint64_t maxFrameNumber = 0) = 0; + + // detachBuffer attempts to remove all ownership of the buffer in the given + // slot from the buffer queue. If this call succeeds, the slot will be + // freed, and there will be no way to obtain the buffer from this interface. + // The freed slot will remain unallocated until either it is selected to + // hold a freshly allocated buffer in dequeueBuffer or a buffer is attached + // to the slot. The buffer must have already been acquired. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - the given slot number is invalid, either because it is + // out of the range [0, NUM_BUFFER_SLOTS) or because the slot + // it refers to is not currently acquired. + virtual status_t detachBuffer(int slot) = 0; + + // attachBuffer attempts to transfer ownership of a buffer to the buffer + // queue. If this call succeeds, it will be as if this buffer was acquired + // from the returned slot number. As such, this call will fail if attaching + // this buffer would cause too many buffers to be simultaneously acquired. + // + // If the buffer is successfully attached, its frameNumber is initialized + // to 0. This must be passed into the releaseBuffer call or else the buffer + // will be deallocated as stale. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - outSlot or buffer were NULL, or the generation number of + // the buffer did not match the buffer queue. + // * INVALID_OPERATION - cannot attach the buffer because it would cause too + // many buffers to be acquired. + // * NO_MEMORY - no free slots available + virtual status_t attachBuffer(int *outSlot, + const sp& buffer) = 0; + + // releaseBuffer releases a buffer slot from the consumer back to the + // BufferQueue. This may be done while the buffer's contents are still + // being accessed. The fence will signal when the buffer is no longer + // in use. frameNumber is used to indentify the exact buffer returned. + // + // If releaseBuffer returns STALE_BUFFER_SLOT, then the consumer must free + // any references to the just-released buffer that it might have, as if it + // had received a onBuffersReleased() call with a mask set for the released + // buffer. + // + // Note that the dependencies on EGL will be removed once we switch to using + // the Android HW Sync HAL. + // + // Return of NO_ERROR means the operation completed as normal. + // + // Return of a positive value means the operation could not be completed + // at this time, but the user should try again later: + // * STALE_BUFFER_SLOT - see above (second paragraph) + // + // Return of a negative value means an error has occurred: + // * BAD_VALUE - one of the following could've happened: + // * the buffer slot was invalid + // * the fence was NULL + // * the buffer slot specified is not in the acquired state + virtual status_t releaseBuffer(int buf, uint64_t frameNumber, + EGLDisplay display, EGLSyncKHR fence, + const sp& releaseFence) = 0; + + // consumerConnect connects a consumer to the BufferQueue. Only one + // consumer may be connected, and when that consumer disconnects the + // BufferQueue is placed into the "abandoned" state, causing most + // interactions with the BufferQueue by the producer to fail. + // controlledByApp indicates whether the consumer is controlled by + // the application. + // + // consumer may not be NULL. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned + // * BAD_VALUE - a NULL consumer was provided + virtual status_t consumerConnect(const sp& consumer, bool controlledByApp) = 0; + + // consumerDisconnect disconnects a consumer from the BufferQueue. All + // buffers will be freed and the BufferQueue is placed in the "abandoned" + // state, causing most interactions with the BufferQueue by the producer to + // fail. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - no consumer is currently connected + virtual status_t consumerDisconnect() = 0; + + // getReleasedBuffers sets the value pointed to by slotMask to a bit set. + // Each bit index with a 1 corresponds to a released buffer slot with that + // index value. In particular, a released buffer is one that has + // been released by the BufferQueue but have not yet been released by the consumer. + // + // This should be called from the onBuffersReleased() callback. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + virtual status_t getReleasedBuffers(uint64_t* slotMask) = 0; + + // setDefaultBufferSize is used to set the size of buffers returned by + // dequeueBuffer when a width and height of zero is requested. Default + // is 1x1. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - either w or h was zero + virtual status_t setDefaultBufferSize(uint32_t w, uint32_t h) = 0; + + // setDefaultMaxBufferCount sets the default value for the maximum buffer + // count (the initial default is 2). If the producer has requested a + // buffer count using setBufferCount, the default buffer count will only + // take effect if the producer sets the count back to zero. + // + // The count must be between 2 and NUM_BUFFER_SLOTS, inclusive. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - bufferCount was out of range (see above). + virtual status_t setDefaultMaxBufferCount(int bufferCount) = 0; + + // disableAsyncBuffer disables the extra buffer used in async mode + // (when both producer and consumer have set their "isControlledByApp" + // flag) and has dequeueBuffer() return WOULD_BLOCK instead. + // + // This can only be called before consumerConnect(). + // + // Return of a value other than NO_ERROR means an error has occurred: + // * INVALID_OPERATION - attempting to call this after consumerConnect. + virtual status_t disableAsyncBuffer() = 0; + + // setMaxAcquiredBufferCount sets the maximum number of buffers that can + // be acquired by the consumer at one time (default 1). This call will + // fail if a producer is connected to the BufferQueue. + // + // maxAcquiredBuffers must be (inclusive) between 1 and MAX_MAX_ACQUIRED_BUFFERS. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - maxAcquiredBuffers was out of range (see above). + // * INVALID_OPERATION - attempting to call this after a producer connected. + virtual status_t setMaxAcquiredBufferCount(int maxAcquiredBuffers) = 0; + + // setConsumerName sets the name used in logging + virtual void setConsumerName(const String8& name) = 0; + + // setDefaultBufferFormat allows the BufferQueue to create + // GraphicBuffers of a defaultFormat if no format is specified + // in dequeueBuffer. + // The initial default is PIXEL_FORMAT_RGBA_8888. + // + // Return of a value other than NO_ERROR means an unknown error has occurred. + virtual status_t setDefaultBufferFormat(PixelFormat defaultFormat) = 0; + + // setDefaultBufferDataSpace is a request to the producer to provide buffers + // of the indicated dataSpace. The producer may ignore this request. + // The initial default is HAL_DATASPACE_UNKNOWN. + // + // Return of a value other than NO_ERROR means an unknown error has occurred. + virtual status_t setDefaultBufferDataSpace( + android_dataspace defaultDataSpace) = 0; + + // setConsumerUsageBits will turn on additional usage bits for dequeueBuffer. + // These are merged with the bits passed to dequeueBuffer. The values are + // enumerated in gralloc.h, e.g. GRALLOC_USAGE_HW_RENDER; the default is 0. + // + // Return of a value other than NO_ERROR means an unknown error has occurred. + virtual status_t setConsumerUsageBits(uint32_t usage) = 0; + + // setTransformHint bakes in rotation to buffers so overlays can be used. + // The values are enumerated in window.h, e.g. + // NATIVE_WINDOW_TRANSFORM_ROT_90. The default is 0 (no transform). + // + // Return of a value other than NO_ERROR means an unknown error has occurred. + virtual status_t setTransformHint(uint32_t hint) = 0; + + // Retrieve the sideband buffer stream, if any. + virtual sp getSidebandStream() const = 0; + + // dump state into a string + virtual void dump(String8& result, const char* prefix) const = 0; + +public: + DECLARE_META_INTERFACE(GraphicBufferConsumer); +}; + +// ---------------------------------------------------------------------------- + +class BnGraphicBufferConsumer : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_IGRAPHICBUFFERCONSUMER_H diff --git a/third_party/android_frameworks_native/include/gui/IGraphicBufferProducer.h b/third_party/android_frameworks_native/include/gui/IGraphicBufferProducer.h new file mode 100644 index 00000000000000..9530de1aa8b434 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IGraphicBufferProducer.h @@ -0,0 +1,502 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_IGRAPHICBUFFERPRODUCER_H +#define ANDROID_GUI_IGRAPHICBUFFERPRODUCER_H + +#include +#include + +#include +#include + +#include + +#include +#include +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class IProducerListener; +class NativeHandle; +class Surface; + +/* + * This class defines the Binder IPC interface for the producer side of + * a queue of graphics buffers. It's used to send graphics data from one + * component to another. For example, a class that decodes video for + * playback might use this to provide frames. This is typically done + * indirectly, through Surface. + * + * The underlying mechanism is a BufferQueue, which implements + * BnGraphicBufferProducer. In normal operation, the producer calls + * dequeueBuffer() to get an empty buffer, fills it with data, then + * calls queueBuffer() to make it available to the consumer. + * + * This class was previously called ISurfaceTexture. + */ +class IGraphicBufferProducer : public IInterface +{ +public: + DECLARE_META_INTERFACE(GraphicBufferProducer); + + enum { + // A flag returned by dequeueBuffer when the client needs to call + // requestBuffer immediately thereafter. + BUFFER_NEEDS_REALLOCATION = 0x1, + // A flag returned by dequeueBuffer when all mirrored slots should be + // released by the client. This flag should always be processed first. + RELEASE_ALL_BUFFERS = 0x2, + }; + + // requestBuffer requests a new buffer for the given index. The server (i.e. + // the IGraphicBufferProducer implementation) assigns the newly created + // buffer to the given slot index, and the client is expected to mirror the + // slot->buffer mapping so that it's not necessary to transfer a + // GraphicBuffer for every dequeue operation. + // + // The slot must be in the range of [0, NUM_BUFFER_SLOTS). + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - one of the two conditions occurred: + // * slot was out of range (see above) + // * buffer specified by the slot is not dequeued + virtual status_t requestBuffer(int slot, sp* buf) = 0; + + // setBufferCount sets the number of buffer slots available. Calling this + // will also cause all buffer slots to be emptied. The caller should empty + // its mirrored copy of the buffer slots when calling this method. + // + // This function should not be called when there are any dequeued buffer + // slots, doing so will result in a BAD_VALUE error returned. + // + // The buffer count should be at most NUM_BUFFER_SLOTS (inclusive), but at least + // the minimum undequeued buffer count (exclusive). The minimum value + // can be obtained by calling query(NATIVE_WINDOW_MIN_UNDEQUEUED_BUFFERS). + // In particular the range is (minUndequeudBuffers, NUM_BUFFER_SLOTS]. + // + // The buffer count may also be set to 0 (the default), to indicate that + // the producer does not wish to set a value. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - one of the below conditions occurred: + // * bufferCount was out of range (see above) + // * client has one or more buffers dequeued + virtual status_t setBufferCount(int bufferCount) = 0; + + // dequeueBuffer requests a new buffer slot for the client to use. Ownership + // of the slot is transfered to the client, meaning that the server will not + // use the contents of the buffer associated with that slot. + // + // The slot index returned may or may not contain a buffer (client-side). + // If the slot is empty the client should call requestBuffer to assign a new + // buffer to that slot. + // + // Once the client is done filling this buffer, it is expected to transfer + // buffer ownership back to the server with either cancelBuffer on + // the dequeued slot or to fill in the contents of its associated buffer + // contents and call queueBuffer. + // + // If dequeueBuffer returns the BUFFER_NEEDS_REALLOCATION flag, the client is + // expected to call requestBuffer immediately. + // + // If dequeueBuffer returns the RELEASE_ALL_BUFFERS flag, the client is + // expected to release all of the mirrored slot->buffer mappings. + // + // The fence parameter will be updated to hold the fence associated with + // the buffer. The contents of the buffer must not be overwritten until the + // fence signals. If the fence is Fence::NO_FENCE, the buffer may be written + // immediately. + // + // The async parameter sets whether we're in asynchronous mode for this + // dequeueBuffer() call. + // + // The width and height parameters must be no greater than the minimum of + // GL_MAX_VIEWPORT_DIMS and GL_MAX_TEXTURE_SIZE (see: glGetIntegerv). + // An error due to invalid dimensions might not be reported until + // updateTexImage() is called. If width and height are both zero, the + // default values specified by setDefaultBufferSize() are used instead. + // + // If the format is 0, the default format will be used. + // + // The usage argument specifies gralloc buffer usage flags. The values + // are enumerated in , e.g. GRALLOC_USAGE_HW_RENDER. These + // will be merged with the usage flags specified by + // IGraphicBufferConsumer::setConsumerUsageBits. + // + // This call will block until a buffer is available to be dequeued. If + // both the producer and consumer are controlled by the app, then this call + // can never block and will return WOULD_BLOCK if no buffer is available. + // + // A non-negative value with flags set (see above) will be returned upon + // success. + // + // Return of a negative means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - both in async mode and buffer count was less than the + // max numbers of buffers that can be allocated at once. + // * INVALID_OPERATION - cannot attach the buffer because it would cause + // too many buffers to be dequeued, either because + // the producer already has a single buffer dequeued + // and did not set a buffer count, or because a + // buffer count was set and this call would cause + // it to be exceeded. + // * WOULD_BLOCK - no buffer is currently available, and blocking is disabled + // since both the producer/consumer are controlled by app + // * NO_MEMORY - out of memory, cannot allocate the graphics buffer. + // + // All other negative values are an unknown error returned downstream + // from the graphics allocator (typically errno). + virtual status_t dequeueBuffer(int* slot, sp* fence, bool async, + uint32_t w, uint32_t h, PixelFormat format, uint32_t usage) = 0; + + // detachBuffer attempts to remove all ownership of the buffer in the given + // slot from the buffer queue. If this call succeeds, the slot will be + // freed, and there will be no way to obtain the buffer from this interface. + // The freed slot will remain unallocated until either it is selected to + // hold a freshly allocated buffer in dequeueBuffer or a buffer is attached + // to the slot. The buffer must have already been dequeued, and the caller + // must already possesses the sp (i.e., must have called + // requestBuffer). + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - the given slot number is invalid, either because it is + // out of the range [0, NUM_BUFFER_SLOTS), or because the slot + // it refers to is not currently dequeued and requested. + virtual status_t detachBuffer(int slot) = 0; + + // detachNextBuffer is equivalent to calling dequeueBuffer, requestBuffer, + // and detachBuffer in sequence, except for two things: + // + // 1) It is unnecessary to know the dimensions, format, or usage of the + // next buffer. + // 2) It will not block, since if it cannot find an appropriate buffer to + // return, it will return an error instead. + // + // Only slots that are free but still contain a GraphicBuffer will be + // considered, and the oldest of those will be returned. outBuffer is + // equivalent to outBuffer from the requestBuffer call, and outFence is + // equivalent to fence from the dequeueBuffer call. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - either outBuffer or outFence were NULL. + // * NO_MEMORY - no slots were found that were both free and contained a + // GraphicBuffer. + virtual status_t detachNextBuffer(sp* outBuffer, + sp* outFence) = 0; + + // attachBuffer attempts to transfer ownership of a buffer to the buffer + // queue. If this call succeeds, it will be as if this buffer was dequeued + // from the returned slot number. As such, this call will fail if attaching + // this buffer would cause too many buffers to be simultaneously dequeued. + // + // If attachBuffer returns the RELEASE_ALL_BUFFERS flag, the caller is + // expected to release all of the mirrored slot->buffer mappings. + // + // A non-negative value with flags set (see above) will be returned upon + // success. + // + // Return of a negative value means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - outSlot or buffer were NULL, invalid combination of + // async mode and buffer count override, or the generation + // number of the buffer did not match the buffer queue. + // * INVALID_OPERATION - cannot attach the buffer because it would cause + // too many buffers to be dequeued, either because + // the producer already has a single buffer dequeued + // and did not set a buffer count, or because a + // buffer count was set and this call would cause + // it to be exceeded. + // * WOULD_BLOCK - no buffer slot is currently available, and blocking is + // disabled since both the producer/consumer are + // controlled by the app. + virtual status_t attachBuffer(int* outSlot, + const sp& buffer) = 0; + + // queueBuffer indicates that the client has finished filling in the + // contents of the buffer associated with slot and transfers ownership of + // that slot back to the server. + // + // It is not valid to call queueBuffer on a slot that is not owned + // by the client or one for which a buffer associated via requestBuffer + // (an attempt to do so will fail with a return value of BAD_VALUE). + // + // In addition, the input must be described by the client (as documented + // below). Any other properties (zero point, etc) + // are client-dependent, and should be documented by the client. + // + // The slot must be in the range of [0, NUM_BUFFER_SLOTS). + // + // Upon success, the output will be filled with meaningful values + // (refer to the documentation below). + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - one of the below conditions occurred: + // * fence was NULL + // * scaling mode was unknown + // * both in async mode and buffer count was less than the + // max numbers of buffers that can be allocated at once + // * slot index was out of range (see above). + // * the slot was not in the dequeued state + // * the slot was enqueued without requesting a buffer + // * crop rect is out of bounds of the buffer dimensions + + struct QueueBufferInput : public Flattenable { + friend class Flattenable; + inline QueueBufferInput(const Parcel& parcel); + // timestamp - a monotonically increasing value in nanoseconds + // isAutoTimestamp - if the timestamp was synthesized at queue time + // dataSpace - description of the contents, interpretation depends on format + // crop - a crop rectangle that's used as a hint to the consumer + // scalingMode - a set of flags from NATIVE_WINDOW_SCALING_* in + // transform - a set of flags from NATIVE_WINDOW_TRANSFORM_* in + // async - if the buffer is queued in asynchronous mode + // fence - a fence that the consumer must wait on before reading the buffer, + // set this to Fence::NO_FENCE if the buffer is ready immediately + // sticky - the sticky transform set in Surface (only used by the LEGACY + // camera mode). + inline QueueBufferInput(int64_t timestamp, bool isAutoTimestamp, + android_dataspace dataSpace, const Rect& crop, int scalingMode, + uint32_t transform, bool async, const sp& fence, + uint32_t sticky = 0) + : timestamp(timestamp), isAutoTimestamp(isAutoTimestamp), + dataSpace(dataSpace), crop(crop), scalingMode(scalingMode), + transform(transform), stickyTransform(sticky), + async(async), fence(fence), surfaceDamage() { } + inline void deflate(int64_t* outTimestamp, bool* outIsAutoTimestamp, + android_dataspace* outDataSpace, + Rect* outCrop, int* outScalingMode, + uint32_t* outTransform, bool* outAsync, sp* outFence, + uint32_t* outStickyTransform = NULL) const { + *outTimestamp = timestamp; + *outIsAutoTimestamp = bool(isAutoTimestamp); + *outDataSpace = dataSpace; + *outCrop = crop; + *outScalingMode = scalingMode; + *outTransform = transform; + *outAsync = bool(async); + *outFence = fence; + if (outStickyTransform != NULL) { + *outStickyTransform = stickyTransform; + } + } + + // Flattenable protocol + size_t getFlattenedSize() const; + size_t getFdCount() const; + status_t flatten(void*& buffer, size_t& size, int*& fds, size_t& count) const; + status_t unflatten(void const*& buffer, size_t& size, int const*& fds, size_t& count); + + const Region& getSurfaceDamage() const { return surfaceDamage; } + void setSurfaceDamage(const Region& damage) { surfaceDamage = damage; } + + private: + int64_t timestamp; + int isAutoTimestamp; + android_dataspace dataSpace; + Rect crop; + int scalingMode; + uint32_t transform; + uint32_t stickyTransform; + int async; + sp fence; + Region surfaceDamage; + }; + + // QueueBufferOutput must be a POD structure + struct __attribute__ ((__packed__)) QueueBufferOutput { + inline QueueBufferOutput() { } + // outWidth - filled with default width applied to the buffer + // outHeight - filled with default height applied to the buffer + // outTransformHint - filled with default transform applied to the buffer + // outNumPendingBuffers - num buffers queued that haven't yet been acquired + // (counting the currently queued buffer) + inline void deflate(uint32_t* outWidth, + uint32_t* outHeight, + uint32_t* outTransformHint, + uint32_t* outNumPendingBuffers) const { + *outWidth = width; + *outHeight = height; + *outTransformHint = transformHint; + *outNumPendingBuffers = numPendingBuffers; + } + inline void inflate(uint32_t inWidth, uint32_t inHeight, + uint32_t inTransformHint, uint32_t inNumPendingBuffers) { + width = inWidth; + height = inHeight; + transformHint = inTransformHint; + numPendingBuffers = inNumPendingBuffers; + } + private: + uint32_t width; + uint32_t height; + uint32_t transformHint; + uint32_t numPendingBuffers; + }; + + virtual status_t queueBuffer(int slot, + const QueueBufferInput& input, QueueBufferOutput* output) = 0; + + // cancelBuffer indicates that the client does not wish to fill in the + // buffer associated with slot and transfers ownership of the slot back to + // the server. + // + // The buffer is not queued for use by the consumer. + // + // The buffer will not be overwritten until the fence signals. The fence + // will usually be the one obtained from dequeueBuffer. + virtual void cancelBuffer(int slot, const sp& fence) = 0; + + // query retrieves some information for this surface + // 'what' tokens allowed are that of NATIVE_WINDOW_* in + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - the buffer queue has been abandoned. + // * BAD_VALUE - what was out of range + virtual int query(int what, int* value) = 0; + + // connect attempts to connect a client API to the IGraphicBufferProducer. + // This must be called before any other IGraphicBufferProducer methods are + // called except for getAllocator. A consumer must be already connected. + // + // This method will fail if the connect was previously called on the + // IGraphicBufferProducer and no corresponding disconnect call was made. + // + // The listener is an optional binder callback object that can be used if + // the producer wants to be notified when the consumer releases a buffer + // back to the BufferQueue. It is also used to detect the death of the + // producer. If only the latter functionality is desired, there is a + // DummyProducerListener class in IProducerListener.h that can be used. + // + // The api should be one of the NATIVE_WINDOW_API_* values in + // + // The producerControlledByApp should be set to true if the producer is hosted + // by an untrusted process (typically app_process-forked processes). If both + // the producer and the consumer are app-controlled then all buffer queues + // will operate in async mode regardless of the async flag. + // + // Upon success, the output will be filled with meaningful data + // (refer to QueueBufferOutput documentation above). + // + // Return of a value other than NO_ERROR means an error has occurred: + // * NO_INIT - one of the following occurred: + // * the buffer queue was abandoned + // * no consumer has yet connected + // * BAD_VALUE - one of the following has occurred: + // * the producer is already connected + // * api was out of range (see above). + // * output was NULL. + // * DEAD_OBJECT - the token is hosted by an already-dead process + // + // Additional negative errors may be returned by the internals, they + // should be treated as opaque fatal unrecoverable errors. + virtual status_t connect(const sp& listener, + int api, bool producerControlledByApp, QueueBufferOutput* output) = 0; + + // disconnect attempts to disconnect a client API from the + // IGraphicBufferProducer. Calling this method will cause any subsequent + // calls to other IGraphicBufferProducer methods to fail except for + // getAllocator and connect. Successfully calling connect after this will + // allow the other methods to succeed again. + // + // This method will fail if the the IGraphicBufferProducer is not currently + // connected to the specified client API. + // + // The api should be one of the NATIVE_WINDOW_API_* values in + // + // Disconnecting from an abandoned IGraphicBufferProducer is legal and + // is considered a no-op. + // + // Return of a value other than NO_ERROR means an error has occurred: + // * BAD_VALUE - one of the following has occurred: + // * the api specified does not match the one that was connected + // * api was out of range (see above). + // * DEAD_OBJECT - the token is hosted by an already-dead process + virtual status_t disconnect(int api) = 0; + + // Attaches a sideband buffer stream to the IGraphicBufferProducer. + // + // A sideband stream is a device-specific mechanism for passing buffers + // from the producer to the consumer without using dequeueBuffer/ + // queueBuffer. If a sideband stream is present, the consumer can choose + // whether to acquire buffers from the sideband stream or from the queued + // buffers. + // + // Passing NULL or a different stream handle will detach the previous + // handle if any. + virtual status_t setSidebandStream(const sp& stream) = 0; + + // Allocates buffers based on the given dimensions/format. + // + // This function will allocate up to the maximum number of buffers + // permitted by the current BufferQueue configuration. It will use the + // given format, dimensions, and usage bits, which are interpreted in the + // same way as for dequeueBuffer, and the async flag must be set the same + // way as for dequeueBuffer to ensure that the correct number of buffers are + // allocated. This is most useful to avoid an allocation delay during + // dequeueBuffer. If there are already the maximum number of buffers + // allocated, this function has no effect. + virtual void allocateBuffers(bool async, uint32_t width, uint32_t height, + PixelFormat format, uint32_t usage) = 0; + + // Sets whether dequeueBuffer is allowed to allocate new buffers. + // + // Normally dequeueBuffer does not discriminate between free slots which + // already have an allocated buffer and those which do not, and will + // allocate a new buffer if the slot doesn't have a buffer or if the slot's + // buffer doesn't match the requested size, format, or usage. This method + // allows the producer to restrict the eligible slots to those which already + // have an allocated buffer of the correct size, format, and usage. If no + // eligible slot is available, dequeueBuffer will block or return an error + // as usual. + virtual status_t allowAllocation(bool allow) = 0; + + // Sets the current generation number of the BufferQueue. + // + // This generation number will be inserted into any buffers allocated by the + // BufferQueue, and any attempts to attach a buffer with a different + // generation number will fail. Buffers already in the queue are not + // affected and will retain their current generation number. The generation + // number defaults to 0. + virtual status_t setGenerationNumber(uint32_t generationNumber) = 0; + + // Returns the name of the connected consumer. + virtual String8 getConsumerName() const = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnGraphicBufferProducer : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_IGRAPHICBUFFERPRODUCER_H diff --git a/third_party/android_frameworks_native/include/gui/IProducerListener.h b/third_party/android_frameworks_native/include/gui/IProducerListener.h new file mode 100644 index 00000000000000..3848a6c850ed69 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/IProducerListener.h @@ -0,0 +1,67 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_IPRODUCERLISTENER_H +#define ANDROID_GUI_IPRODUCERLISTENER_H + +#include + +#include + +namespace android { + +// ProducerListener is the interface through which the BufferQueue notifies the +// producer of events that the producer may wish to react to. Because the +// producer will generally have a mutex that is locked during calls from the +// producer to the BufferQueue, these calls from the BufferQueue to the +// producer *MUST* be called only when the BufferQueue mutex is NOT locked. + +class ProducerListener : public virtual RefBase +{ +public: + ProducerListener() {} + virtual ~ProducerListener() {} + + // onBufferReleased is called from IGraphicBufferConsumer::releaseBuffer to + // notify the producer that a new buffer is free and ready to be dequeued. + // + // This is called without any lock held and can be called concurrently by + // multiple threads. + virtual void onBufferReleased() = 0; // Asynchronous +}; + +class IProducerListener : public ProducerListener, public IInterface +{ +public: + DECLARE_META_INTERFACE(ProducerListener) +}; + +class BnProducerListener : public BnInterface +{ +public: + virtual status_t onTransact(uint32_t code, const Parcel& data, + Parcel* reply, uint32_t flags = 0); +}; + +class DummyProducerListener : public BnProducerListener +{ +public: + virtual void onBufferReleased() {} +}; + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/ISensorEventConnection.h b/third_party/android_frameworks_native/include/gui/ISensorEventConnection.h new file mode 100644 index 00000000000000..f64c6b8604ebab --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/ISensorEventConnection.h @@ -0,0 +1,59 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_ISENSOR_EVENT_CONNECTION_H +#define ANDROID_GUI_ISENSOR_EVENT_CONNECTION_H + +#include +#include + +#include +#include + +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class BitTube; + +class ISensorEventConnection : public IInterface +{ +public: + DECLARE_META_INTERFACE(SensorEventConnection); + + virtual sp getSensorChannel() const = 0; + virtual status_t enableDisable(int handle, bool enabled, nsecs_t samplingPeriodNs, + nsecs_t maxBatchReportLatencyNs, int reservedFlags) = 0; + virtual status_t setEventRate(int handle, nsecs_t ns) = 0; + virtual status_t flush() = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnSensorEventConnection : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_ISENSOR_EVENT_CONNECTION_H diff --git a/third_party/android_frameworks_native/include/gui/ISensorServer.h b/third_party/android_frameworks_native/include/gui/ISensorServer.h new file mode 100644 index 00000000000000..3dca2a37398e4a --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/ISensorServer.h @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_ISENSORSERVER_H +#define ANDROID_GUI_ISENSORSERVER_H + +#include +#include + +#include +#include + +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class Sensor; +class ISensorEventConnection; +class String8; + +class ISensorServer : public IInterface +{ +public: + DECLARE_META_INTERFACE(SensorServer); + + virtual Vector getSensorList(const String16& opPackageName) = 0; + virtual sp createSensorEventConnection(const String8& packageName, + int mode, const String16& opPackageName) = 0; + virtual int32_t isDataInjectionEnabled() = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnSensorServer : public BnInterface +{ +public: + virtual status_t onTransact( uint32_t code, + const Parcel& data, + Parcel* reply, + uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_ISENSORSERVER_H diff --git a/third_party/android_frameworks_native/include/gui/ISurfaceComposer.h b/third_party/android_frameworks_native/include/gui/ISurfaceComposer.h new file mode 100644 index 00000000000000..6e3fc5a6decd09 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/ISurfaceComposer.h @@ -0,0 +1,201 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_ISURFACE_COMPOSER_H +#define ANDROID_GUI_ISURFACE_COMPOSER_H + +#include +#include + +#include +#include +#include +#include + +#include + +#include + +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class ComposerState; +class DisplayState; +struct DisplayInfo; +struct DisplayStatInfo; +class IDisplayEventConnection; +class IMemoryHeap; +class Rect; + +/* + * This class defines the Binder IPC interface for accessing various + * SurfaceFlinger features. + */ +class ISurfaceComposer: public IInterface { +public: + DECLARE_META_INTERFACE(SurfaceComposer); + + // flags for setTransactionState() + enum { + eSynchronous = 0x01, + eAnimation = 0x02, + }; + + enum { + eDisplayIdMain = 0, + eDisplayIdHdmi = 1, +#ifdef QTI_BSP + eDisplayIdTertiary = 2 +#endif + }; + + enum Rotation { + eRotateNone = 0, + eRotate90 = 1, + eRotate180 = 2, + eRotate270 = 3 + }; + + /* create connection with surface flinger, requires + * ACCESS_SURFACE_FLINGER permission + */ + virtual sp createConnection() = 0; + + /* create a graphic buffer allocator + */ + virtual sp createGraphicBufferAlloc() = 0; + + /* return an IDisplayEventConnection */ + virtual sp createDisplayEventConnection() = 0; + + /* create a virtual display + * requires ACCESS_SURFACE_FLINGER permission. + */ + virtual sp createDisplay(const String8& displayName, + bool secure) = 0; + + /* destroy a virtual display + * requires ACCESS_SURFACE_FLINGER permission. + */ + virtual void destroyDisplay(const sp& display) = 0; + + /* get the token for the existing default displays. possible values + * for id are eDisplayIdMain and eDisplayIdHdmi. + */ + virtual sp getBuiltInDisplay(int32_t id) = 0; + + /* open/close transactions. requires ACCESS_SURFACE_FLINGER permission */ + virtual void setTransactionState(const Vector& state, + const Vector& displays, uint32_t flags) = 0; + + /* signal that we're done booting. + * Requires ACCESS_SURFACE_FLINGER permission + */ + virtual void bootFinished() = 0; + + /* verify that an IGraphicBufferProducer was created by SurfaceFlinger. + */ + virtual bool authenticateSurfaceTexture( + const sp& surface) const = 0; + + /* set display power mode. depending on the mode, it can either trigger + * screen on, off or low power mode and wait for it to complete. + * requires ACCESS_SURFACE_FLINGER permission. + */ + virtual void setPowerMode(const sp& display, int mode) = 0; + + /* returns information for each configuration of the given display + * intended to be used to get information about built-in displays */ + virtual status_t getDisplayConfigs(const sp& display, + Vector* configs) = 0; + + /* returns display statistics for a given display + * intended to be used by the media framework to properly schedule + * video frames */ + virtual status_t getDisplayStats(const sp& display, + DisplayStatInfo* stats) = 0; + + /* indicates which of the configurations returned by getDisplayInfo is + * currently active */ + virtual int getActiveConfig(const sp& display) = 0; + + /* specifies which configuration (of those returned by getDisplayInfo) + * should be used */ + virtual status_t setActiveConfig(const sp& display, int id) = 0; + + /* Capture the specified screen. requires READ_FRAME_BUFFER permission + * This function will fail if there is a secure window on screen. + */ + virtual status_t captureScreen(const sp& display, + const sp& producer, + Rect sourceCrop, uint32_t reqWidth, uint32_t reqHeight, + uint32_t minLayerZ, uint32_t maxLayerZ, + bool useIdentityTransform, + Rotation rotation = eRotateNone, + bool isCpuConsumer = false) = 0; + + /* Clears the frame statistics for animations. + * + * Requires the ACCESS_SURFACE_FLINGER permission. + */ + virtual status_t clearAnimationFrameStats() = 0; + + /* Gets the frame statistics for animations. + * + * Requires the ACCESS_SURFACE_FLINGER permission. + */ + virtual status_t getAnimationFrameStats(FrameStats* outStats) const = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnSurfaceComposer: public BnInterface { +public: + enum { + // Note: BOOT_FINISHED must remain this value, it is called from + // Java by ActivityManagerService. + BOOT_FINISHED = IBinder::FIRST_CALL_TRANSACTION, + CREATE_CONNECTION, + CREATE_GRAPHIC_BUFFER_ALLOC, + CREATE_DISPLAY_EVENT_CONNECTION, + CREATE_DISPLAY, + DESTROY_DISPLAY, + GET_BUILT_IN_DISPLAY, + SET_TRANSACTION_STATE, + AUTHENTICATE_SURFACE, + GET_DISPLAY_CONFIGS, + GET_ACTIVE_CONFIG, + SET_ACTIVE_CONFIG, + CONNECT_DISPLAY, + CAPTURE_SCREEN, + CLEAR_ANIMATION_FRAME_STATS, + GET_ANIMATION_FRAME_STATS, + SET_POWER_MODE, + GET_DISPLAY_STATS, + }; + + virtual status_t onTransact(uint32_t code, const Parcel& data, + Parcel* reply, uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_GUI_ISURFACE_COMPOSER_H diff --git a/third_party/android_frameworks_native/include/gui/ISurfaceComposerClient.h b/third_party/android_frameworks_native/include/gui/ISurfaceComposerClient.h new file mode 100644 index 00000000000000..d3e8b8ba13f1bc --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/ISurfaceComposerClient.h @@ -0,0 +1,95 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_ISURFACE_COMPOSER_CLIENT_H +#define ANDROID_GUI_ISURFACE_COMPOSER_CLIENT_H + +#include +#include + +#include +#include + +#include + +#include +#include + +namespace android { +// ---------------------------------------------------------------------------- + +class IGraphicBufferProducer; + +class ISurfaceComposerClient : public IInterface +{ +public: + DECLARE_META_INTERFACE(SurfaceComposerClient); + + // flags for createSurface() + enum { // (keep in sync with Surface.java) + eHidden = 0x00000004, + eDestroyBackbuffer = 0x00000020, + eSecure = 0x00000080, + eNonPremultiplied = 0x00000100, + eOpaque = 0x00000400, + eProtectedByApp = 0x00000800, + eProtectedByDRM = 0x00001000, + eCursorWindow = 0x00002000, + + eFXSurfaceNormal = 0x00000000, + eFXSurfaceBlur = 0x00010000, + eFXSurfaceDim = 0x00020000, + eFXSurfaceMask = 0x000F0000, + }; + + /* + * Requires ACCESS_SURFACE_FLINGER permission + */ + virtual status_t createSurface( + const String8& name, uint32_t w, uint32_t h, + PixelFormat format, uint32_t flags, + sp* handle, + sp* gbp) = 0; + + /* + * Requires ACCESS_SURFACE_FLINGER permission + */ + virtual status_t destroySurface(const sp& handle) = 0; + + /* + * Requires ACCESS_SURFACE_FLINGER permission + */ + virtual status_t clearLayerFrameStats(const sp& handle) const = 0; + + /* + * Requires ACCESS_SURFACE_FLINGER permission + */ + virtual status_t getLayerFrameStats(const sp& handle, FrameStats* outStats) const = 0; +}; + +// ---------------------------------------------------------------------------- + +class BnSurfaceComposerClient: public BnInterface { +public: + virtual status_t onTransact(uint32_t code, const Parcel& data, + Parcel* reply, uint32_t flags = 0); +}; + +// ---------------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_GUI_ISURFACE_COMPOSER_CLIENT_H diff --git a/third_party/android_frameworks_native/include/gui/Sensor.h b/third_party/android_frameworks_native/include/gui/Sensor.h new file mode 100644 index 00000000000000..8142be635204dc --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/Sensor.h @@ -0,0 +1,113 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SENSOR_H +#define ANDROID_GUI_SENSOR_H + +#include +#include + +#include +#include +#include +#include + +#include + +#include + +// ---------------------------------------------------------------------------- +// Concrete types for the NDK +struct ASensor { }; + +// ---------------------------------------------------------------------------- +namespace android { +// ---------------------------------------------------------------------------- + +class Parcel; + +// ---------------------------------------------------------------------------- + +class Sensor : public ASensor, public LightFlattenable +{ +public: + enum { + TYPE_ACCELEROMETER = ASENSOR_TYPE_ACCELEROMETER, + TYPE_MAGNETIC_FIELD = ASENSOR_TYPE_MAGNETIC_FIELD, + TYPE_GYROSCOPE = ASENSOR_TYPE_GYROSCOPE, + TYPE_LIGHT = ASENSOR_TYPE_LIGHT, + TYPE_PROXIMITY = ASENSOR_TYPE_PROXIMITY + }; + + Sensor(); + Sensor(struct sensor_t const* hwSensor, int halVersion = 0); + ~Sensor(); + + const String8& getName() const; + const String8& getVendor() const; + int32_t getHandle() const; + int32_t getType() const; + float getMinValue() const; + float getMaxValue() const; + float getResolution() const; + float getPowerUsage() const; + int32_t getMinDelay() const; + nsecs_t getMinDelayNs() const; + int32_t getVersion() const; + uint32_t getFifoReservedEventCount() const; + uint32_t getFifoMaxEventCount() const; + const String8& getStringType() const; + const String8& getRequiredPermission() const; + bool isRequiredPermissionRuntime() const; + int32_t getRequiredAppOp() const; + int32_t getMaxDelay() const; + uint32_t getFlags() const; + bool isWakeUpSensor() const; + int32_t getReportingMode() const; + + // LightFlattenable protocol + inline bool isFixedSize() const { return false; } + size_t getFlattenedSize() const; + status_t flatten(void* buffer, size_t size) const; + status_t unflatten(void const* buffer, size_t size); + +private: + String8 mName; + String8 mVendor; + int32_t mHandle; + int32_t mType; + float mMinValue; + float mMaxValue; + float mResolution; + float mPower; + int32_t mMinDelay; + int32_t mVersion; + uint32_t mFifoReservedEventCount; + uint32_t mFifoMaxEventCount; + String8 mStringType; + String8 mRequiredPermission; + bool mRequiredPermissionRuntime = false; + int32_t mRequiredAppOp; + int32_t mMaxDelay; + uint32_t mFlags; + static void flattenString8(void*& buffer, size_t& size, const String8& string8); + static bool unflattenString8(void const*& buffer, size_t& size, String8& outputString8); +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_SENSOR_H diff --git a/third_party/android_frameworks_native/include/gui/SensorEventQueue.h b/third_party/android_frameworks_native/include/gui/SensorEventQueue.h new file mode 100644 index 00000000000000..e5b9fc59847a9b --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/SensorEventQueue.h @@ -0,0 +1,98 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_SENSOR_EVENT_QUEUE_H +#define ANDROID_SENSOR_EVENT_QUEUE_H + +#include +#include + +#include +#include +#include +#include + +#include + +// ---------------------------------------------------------------------------- +#define WAKE_UP_SENSOR_EVENT_NEEDS_ACK (1U << 31) +struct ALooper; +struct ASensorEvent; + +// Concrete types for the NDK +struct ASensorEventQueue { + ALooper* looper; +}; + +// ---------------------------------------------------------------------------- +namespace android { +// ---------------------------------------------------------------------------- + +class ISensorEventConnection; +class Sensor; +class Looper; + +// ---------------------------------------------------------------------------- + +class SensorEventQueue : public ASensorEventQueue, public RefBase +{ +public: + + enum { MAX_RECEIVE_BUFFER_EVENT_COUNT = 256 }; + + SensorEventQueue(const sp& connection); + virtual ~SensorEventQueue(); + virtual void onFirstRef(); + + int getFd() const; + + static ssize_t write(const sp& tube, + ASensorEvent const* events, size_t numEvents); + + ssize_t read(ASensorEvent* events, size_t numEvents); + + status_t waitForEvent() const; + status_t wake() const; + + status_t enableSensor(Sensor const* sensor) const; + status_t disableSensor(Sensor const* sensor) const; + status_t setEventRate(Sensor const* sensor, nsecs_t ns) const; + + // these are here only to support SensorManager.java + status_t enableSensor(int32_t handle, int32_t samplingPeriodUs, int maxBatchReportLatencyUs, + int reservedFlags) const; + status_t disableSensor(int32_t handle) const; + status_t flush() const; + // Send an ack for every wake_up sensor event that is set to WAKE_UP_SENSOR_EVENT_NEEDS_ACK. + void sendAck(const ASensorEvent* events, int count); + + status_t injectSensorEvent(const ASensorEvent& event); +private: + sp getLooper() const; + sp mSensorEventConnection; + sp mSensorChannel; + mutable Mutex mLock; + mutable sp mLooper; + ASensorEvent* mRecBuffer; + size_t mAvailable; + size_t mConsumed; + uint32_t mNumAcksToSend; +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_SENSOR_EVENT_QUEUE_H diff --git a/third_party/android_frameworks_native/include/gui/SensorManager.h b/third_party/android_frameworks_native/include/gui/SensorManager.h new file mode 100644 index 00000000000000..0cff46c076231f --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/SensorManager.h @@ -0,0 +1,84 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SENSOR_MANAGER_H +#define ANDROID_GUI_SENSOR_MANAGER_H + +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +// ---------------------------------------------------------------------------- +// Concrete types for the NDK +struct ASensorManager { }; + +// ---------------------------------------------------------------------------- +namespace android { +// ---------------------------------------------------------------------------- + +class ISensorServer; +class Sensor; +class SensorEventQueue; +// ---------------------------------------------------------------------------- + +class SensorManager : + public ASensorManager +{ +public: + static SensorManager& getInstanceForPackage(const String16& packageName); + ~SensorManager(); + + ssize_t getSensorList(Sensor const* const** list) const; + Sensor const* getDefaultSensor(int type); + sp createEventQueue(String8 packageName = String8(""), int mode = 0); + bool isDataInjectionEnabled(); + +private: + // DeathRecipient interface + void sensorManagerDied(); + + SensorManager(const String16& opPackageName); + status_t assertStateLocked() const; + +private: + static Mutex sLock; + static std::map sPackageInstances; + + mutable Mutex mLock; + mutable sp mSensorServer; + mutable Sensor const** mSensorList; + mutable Vector mSensors; + mutable sp mDeathObserver; + const String16 mOpPackageName; +}; + +// ---------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_SENSOR_MANAGER_H diff --git a/third_party/android_frameworks_native/include/gui/StreamSplitter.h b/third_party/android_frameworks_native/include/gui/StreamSplitter.h new file mode 100644 index 00000000000000..8f47eb47ac444c --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/StreamSplitter.h @@ -0,0 +1,184 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_STREAMSPLITTER_H +#define ANDROID_GUI_STREAMSPLITTER_H + +#include +#include + +#include +#include +#include +#include + +namespace android { + +class GraphicBuffer; +class IGraphicBufferConsumer; +class IGraphicBufferProducer; + +// StreamSplitter is an autonomous class that manages one input BufferQueue +// and multiple output BufferQueues. By using the buffer attach and detach logic +// in BufferQueue, it is able to present the illusion of a single split +// BufferQueue, where each buffer queued to the input is available to be +// acquired by each of the outputs, and is able to be dequeued by the input +// again only once all of the outputs have released it. +class StreamSplitter : public BnConsumerListener { +public: + // createSplitter creates a new splitter, outSplitter, using inputQueue as + // the input BufferQueue. Output BufferQueues must be added using addOutput + // before queueing any buffers to the input. + // + // A return value other than NO_ERROR means that an error has occurred and + // outSplitter has not been modified. BAD_VALUE is returned if inputQueue or + // outSplitter is NULL. See IGraphicBufferConsumer::consumerConnect for + // explanations of other error codes. + static status_t createSplitter(const sp& inputQueue, + sp* outSplitter); + + // addOutput adds an output BufferQueue to the splitter. The splitter + // connects to outputQueue as a CPU producer, and any buffers queued + // to the input will be queued to each output. It is assumed that all of the + // outputs are added before any buffers are queued on the input. If any + // output is abandoned by its consumer, the splitter will abandon its input + // queue (see onAbandoned). + // + // A return value other than NO_ERROR means that an error has occurred and + // outputQueue has not been added to the splitter. BAD_VALUE is returned if + // outputQueue is NULL. See IGraphicBufferProducer::connect for explanations + // of other error codes. + status_t addOutput(const sp& outputQueue); + + // setName sets the consumer name of the input queue + void setName(const String8& name); + +private: + // From IConsumerListener + // + // During this callback, we store some tracking information, detach the + // buffer from the input, and attach it to each of the outputs. This call + // can block if there are too many outstanding buffers. If it blocks, it + // will resume when onBufferReleasedByOutput releases a buffer back to the + // input. + virtual void onFrameAvailable(const BufferItem& item); + + // From IConsumerListener + // We don't care about released buffers because we detach each buffer as + // soon as we acquire it. See the comment for onBufferReleased below for + // some clarifying notes about the name. + virtual void onBuffersReleased() {} + + // From IConsumerListener + // We don't care about sideband streams, since we won't be splitting them + virtual void onSidebandStreamChanged() {} + + // This is the implementation of the onBufferReleased callback from + // IProducerListener. It gets called from an OutputListener (see below), and + // 'from' is which producer interface from which the callback was received. + // + // During this callback, we detach the buffer from the output queue that + // generated the callback, update our state tracking to see if this is the + // last output releasing the buffer, and if so, release it to the input. + // If we release the buffer to the input, we allow a blocked + // onFrameAvailable call to proceed. + void onBufferReleasedByOutput(const sp& from); + + // When this is called, the splitter disconnects from (i.e., abandons) its + // input queue and signals any waiting onFrameAvailable calls to wake up. + // It still processes callbacks from other outputs, but only detaches their + // buffers so they can continue operating until they run out of buffers to + // acquire. This must be called with mMutex locked. + void onAbandonedLocked(); + + // This is a thin wrapper class that lets us determine which BufferQueue + // the IProducerListener::onBufferReleased callback is associated with. We + // create one of these per output BufferQueue, and then pass the producer + // into onBufferReleasedByOutput above. + class OutputListener : public BnProducerListener, + public IBinder::DeathRecipient { + public: + OutputListener(const sp& splitter, + const sp& output); + virtual ~OutputListener(); + + // From IProducerListener + virtual void onBufferReleased(); + + // From IBinder::DeathRecipient + virtual void binderDied(const wp& who); + + private: + sp mSplitter; + sp mOutput; + }; + + class BufferTracker : public LightRefBase { + public: + BufferTracker(const sp& buffer); + + const sp& getBuffer() const { return mBuffer; } + const sp& getMergedFence() const { return mMergedFence; } + + void mergeFence(const sp& with); + + // Returns the new value + // Only called while mMutex is held + size_t incrementReleaseCountLocked() { return ++mReleaseCount; } + + private: + // Only destroy through LightRefBase + friend LightRefBase; + ~BufferTracker(); + + // Disallow copying + BufferTracker(const BufferTracker& other); + BufferTracker& operator=(const BufferTracker& other); + + sp mBuffer; // One instance that holds this native handle + sp mMergedFence; + size_t mReleaseCount; + }; + + // Only called from createSplitter + StreamSplitter(const sp& inputQueue); + + // Must be accessed through RefBase + virtual ~StreamSplitter(); + + static const int MAX_OUTSTANDING_BUFFERS = 2; + + // mIsAbandoned is set to true when an output dies. Once the StreamSplitter + // has been abandoned, it will continue to detach buffers from other + // outputs, but it will disconnect from the input and not attempt to + // communicate with it further. + bool mIsAbandoned; + + Mutex mMutex; + Condition mReleaseCondition; + int mOutstandingBuffers; + sp mInput; + Vector > mOutputs; + + // Map of GraphicBuffer IDs (GraphicBuffer::getId()) to buffer tracking + // objects (which are mostly for counting how many outputs have released the + // buffer, but also contain merged release fences). + KeyedVector > mBuffers; +}; + +} // namespace android + +#endif diff --git a/third_party/android_frameworks_native/include/gui/Surface.h b/third_party/android_frameworks_native/include/gui/Surface.h new file mode 100644 index 00000000000000..72f1067076ccd3 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/Surface.h @@ -0,0 +1,324 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SURFACE_H +#define ANDROID_GUI_SURFACE_H + +#include +#include + +#include +#include + +#include +#include +#include + +struct ANativeWindow_Buffer; + +namespace android { + +/* + * An implementation of ANativeWindow that feeds graphics buffers into a + * BufferQueue. + * + * This is typically used by programs that want to render frames through + * some means (maybe OpenGL, a software renderer, or a hardware decoder) + * and have the frames they create forwarded to SurfaceFlinger for + * compositing. For example, a video decoder could render a frame and call + * eglSwapBuffers(), which invokes ANativeWindow callbacks defined by + * Surface. Surface then forwards the buffers through Binder IPC + * to the BufferQueue's producer interface, providing the new frame to a + * consumer such as GLConsumer. + */ +class Surface + : public ANativeObjectBase +{ +public: + + /* + * creates a Surface from the given IGraphicBufferProducer (which concrete + * implementation is a BufferQueue). + * + * Surface is mainly state-less while it's disconnected, it can be + * viewed as a glorified IGraphicBufferProducer holder. It's therefore + * safe to create other Surfaces from the same IGraphicBufferProducer. + * + * However, once a Surface is connected, it'll prevent other Surfaces + * referring to the same IGraphicBufferProducer to become connected and + * therefore prevent them to be used as actual producers of buffers. + * + * the controlledByApp flag indicates that this Surface (producer) is + * controlled by the application. This flag is used at connect time. + */ + Surface(const sp& bufferProducer, bool controlledByApp = false); + + /* getIGraphicBufferProducer() returns the IGraphicBufferProducer this + * Surface was created with. Usually it's an error to use the + * IGraphicBufferProducer while the Surface is connected. + */ + sp getIGraphicBufferProducer() const; + + /* convenience function to check that the given surface is non NULL as + * well as its IGraphicBufferProducer */ + static bool isValid(const sp& surface) { + return surface != NULL && surface->getIGraphicBufferProducer() != NULL; + } + + /* Attaches a sideband buffer stream to the Surface's IGraphicBufferProducer. + * + * A sideband stream is a device-specific mechanism for passing buffers + * from the producer to the consumer without using dequeueBuffer/ + * queueBuffer. If a sideband stream is present, the consumer can choose + * whether to acquire buffers from the sideband stream or from the queued + * buffers. + * + * Passing NULL or a different stream handle will detach the previous + * handle if any. + */ + void setSidebandStream(const sp& stream); + + /* Allocates buffers based on the current dimensions/format. + * + * This function will allocate up to the maximum number of buffers + * permitted by the current BufferQueue configuration. It will use the + * default format and dimensions. This is most useful to avoid an allocation + * delay during dequeueBuffer. If there are already the maximum number of + * buffers allocated, this function has no effect. + */ + void allocateBuffers(); + + /* Sets the generation number on the IGraphicBufferProducer and updates the + * generation number on any buffers attached to the Surface after this call. + * See IGBP::setGenerationNumber for more information. */ + status_t setGenerationNumber(uint32_t generationNumber); + + // See IGraphicBufferProducer::getConsumerName + String8 getConsumerName() const; + +protected: + virtual ~Surface(); + +private: + // can't be copied + Surface& operator = (const Surface& rhs); + Surface(const Surface& rhs); + + // ANativeWindow hooks + static int hook_cancelBuffer(ANativeWindow* window, + ANativeWindowBuffer* buffer, int fenceFd); + static int hook_dequeueBuffer(ANativeWindow* window, + ANativeWindowBuffer** buffer, int* fenceFd); + static int hook_perform(ANativeWindow* window, int operation, ...); + static int hook_query(const ANativeWindow* window, int what, int* value); + static int hook_queueBuffer(ANativeWindow* window, + ANativeWindowBuffer* buffer, int fenceFd); + static int hook_setSwapInterval(ANativeWindow* window, int interval); + + static int hook_cancelBuffer_DEPRECATED(ANativeWindow* window, + ANativeWindowBuffer* buffer); + static int hook_dequeueBuffer_DEPRECATED(ANativeWindow* window, + ANativeWindowBuffer** buffer); + static int hook_lockBuffer_DEPRECATED(ANativeWindow* window, + ANativeWindowBuffer* buffer); + static int hook_queueBuffer_DEPRECATED(ANativeWindow* window, + ANativeWindowBuffer* buffer); + + int dispatchConnect(va_list args); + int dispatchDisconnect(va_list args); + int dispatchSetBufferCount(va_list args); + int dispatchSetBuffersGeometry(va_list args); + int dispatchSetBuffersDimensions(va_list args); + int dispatchSetBuffersUserDimensions(va_list args); + int dispatchSetBuffersFormat(va_list args); + int dispatchSetScalingMode(va_list args); + int dispatchSetBuffersTransform(va_list args); + int dispatchSetBuffersStickyTransform(va_list args); + int dispatchSetBuffersTimestamp(va_list args); + int dispatchSetCrop(va_list args); + int dispatchSetPostTransformCrop(va_list args); + int dispatchSetUsage(va_list args); + int dispatchLock(va_list args); + int dispatchUnlockAndPost(va_list args); + int dispatchSetSidebandStream(va_list args); + int dispatchSetBuffersDataSpace(va_list args); + int dispatchSetSurfaceDamage(va_list args); + +protected: + virtual int dequeueBuffer(ANativeWindowBuffer** buffer, int* fenceFd); + virtual int cancelBuffer(ANativeWindowBuffer* buffer, int fenceFd); + virtual int queueBuffer(ANativeWindowBuffer* buffer, int fenceFd); + virtual int perform(int operation, va_list args); + virtual int query(int what, int* value) const; + virtual int setSwapInterval(int interval); + + virtual int lockBuffer_DEPRECATED(ANativeWindowBuffer* buffer); + + virtual int connect(int api); + virtual int disconnect(int api); + virtual int setBufferCount(int bufferCount); + virtual int setBuffersDimensions(uint32_t width, uint32_t height); + virtual int setBuffersUserDimensions(uint32_t width, uint32_t height); + virtual int setBuffersFormat(PixelFormat format); + virtual int setScalingMode(int mode); + virtual int setBuffersTransform(uint32_t transform); + virtual int setBuffersStickyTransform(uint32_t transform); + virtual int setBuffersTimestamp(int64_t timestamp); + virtual int setBuffersDataSpace(android_dataspace dataSpace); + virtual int setCrop(Rect const* rect); + virtual int setUsage(uint32_t reqUsage); + virtual void setSurfaceDamage(android_native_rect_t* rects, size_t numRects); + +public: + virtual int lock(ANativeWindow_Buffer* outBuffer, ARect* inOutDirtyBounds); + virtual int unlockAndPost(); + + virtual int connect(int api, const sp& listener); + virtual int detachNextBuffer(sp* outBuffer, + sp* outFence); + virtual int attachBuffer(ANativeWindowBuffer*); + +protected: + enum { NUM_BUFFER_SLOTS = BufferQueue::NUM_BUFFER_SLOTS }; + enum { DEFAULT_FORMAT = PIXEL_FORMAT_RGBA_8888 }; + +private: + void freeAllBuffers(); + int getSlotFromBufferLocked(android_native_buffer_t* buffer) const; + + struct BufferSlot { + sp buffer; + Region dirtyRegion; + }; + + // mSurfaceTexture is the interface to the surface texture server. All + // operations on the surface texture client ultimately translate into + // interactions with the server using this interface. + // TODO: rename to mBufferProducer + sp mGraphicBufferProducer; + + // mSlots stores the buffers that have been allocated for each buffer slot. + // It is initialized to null pointers, and gets filled in with the result of + // IGraphicBufferProducer::requestBuffer when the client dequeues a buffer from a + // slot that has not yet been used. The buffer allocated to a slot will also + // be replaced if the requested buffer usage or geometry differs from that + // of the buffer allocated to a slot. + BufferSlot mSlots[NUM_BUFFER_SLOTS]; + + // mReqWidth is the buffer width that will be requested at the next dequeue + // operation. It is initialized to 1. + uint32_t mReqWidth; + + // mReqHeight is the buffer height that will be requested at the next + // dequeue operation. It is initialized to 1. + uint32_t mReqHeight; + + // mReqFormat is the buffer pixel format that will be requested at the next + // deuque operation. It is initialized to PIXEL_FORMAT_RGBA_8888. + PixelFormat mReqFormat; + + // mReqUsage is the set of buffer usage flags that will be requested + // at the next deuque operation. It is initialized to 0. + uint32_t mReqUsage; + + // mTimestamp is the timestamp that will be used for the next buffer queue + // operation. It defaults to NATIVE_WINDOW_TIMESTAMP_AUTO, which means that + // a timestamp is auto-generated when queueBuffer is called. + int64_t mTimestamp; + + // mDataSpace is the buffer dataSpace that will be used for the next buffer + // queue operation. It defaults to HAL_DATASPACE_UNKNOWN, which + // means that the buffer contains some type of color data. + android_dataspace mDataSpace; + + // mCrop is the crop rectangle that will be used for the next buffer + // that gets queued. It is set by calling setCrop. + Rect mCrop; + + // mScalingMode is the scaling mode that will be used for the next + // buffers that get queued. It is set by calling setScalingMode. + int mScalingMode; + + // mTransform is the transform identifier that will be used for the next + // buffer that gets queued. It is set by calling setTransform. + uint32_t mTransform; + + // mStickyTransform is a transform that is applied on top of mTransform + // in each buffer that is queued. This is typically used to force the + // compositor to apply a transform, and will prevent the transform hint + // from being set by the compositor. + uint32_t mStickyTransform; + + // mDefaultWidth is default width of the buffers, regardless of the + // native_window_set_buffers_dimensions call. + uint32_t mDefaultWidth; + + // mDefaultHeight is default height of the buffers, regardless of the + // native_window_set_buffers_dimensions call. + uint32_t mDefaultHeight; + + // mUserWidth, if non-zero, is an application-specified override + // of mDefaultWidth. This is lower priority than the width set by + // native_window_set_buffers_dimensions. + uint32_t mUserWidth; + + // mUserHeight, if non-zero, is an application-specified override + // of mDefaultHeight. This is lower priority than the height set + // by native_window_set_buffers_dimensions. + uint32_t mUserHeight; + + // mTransformHint is the transform probably applied to buffers of this + // window. this is only a hint, actual transform may differ. + uint32_t mTransformHint; + + // mProducerControlledByApp whether this buffer producer is controlled + // by the application + bool mProducerControlledByApp; + + // mSwapIntervalZero set if we should drop buffers at queue() time to + // achieve an asynchronous swap interval + bool mSwapIntervalZero; + + // mConsumerRunningBehind whether the consumer is running more than + // one buffer behind the producer. + mutable bool mConsumerRunningBehind; + + // mMutex is the mutex used to prevent concurrent access to the member + // variables of Surface objects. It must be locked whenever the + // member variables are accessed. + mutable Mutex mMutex; + + // must be used from the lock/unlock thread + sp mLockedBuffer; + sp mPostedBuffer; + bool mConnectedToCpu; + + // When a CPU producer is attached, this reflects the region that the + // producer wished to update as well as whether the Surface was able to copy + // the previous buffer back to allow a partial update. + // + // When a non-CPU producer is attached, this reflects the surface damage + // (the change since the previous frame) passed in by the producer. + Region mDirtyRegion; + + // Stores the current generation number. See setGenerationNumber and + // IGraphicBufferProducer::setGenerationNumber for more information. + uint32_t mGenerationNumber; +}; + +}; // namespace android + +#endif // ANDROID_GUI_SURFACE_H diff --git a/third_party/android_frameworks_native/include/gui/SurfaceComposerClient.h b/third_party/android_frameworks_native/include/gui/SurfaceComposerClient.h new file mode 100644 index 00000000000000..9ec3f23491eb23 --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/SurfaceComposerClient.h @@ -0,0 +1,242 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SURFACE_COMPOSER_CLIENT_H +#define ANDROID_GUI_SURFACE_COMPOSER_CLIENT_H + +#include +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include + +namespace android { + +// --------------------------------------------------------------------------- + +class DisplayInfo; +class Composer; +class ISurfaceComposerClient; +class IGraphicBufferProducer; +class Region; + +// --------------------------------------------------------------------------- + +class SurfaceComposerClient : public RefBase +{ + friend class Composer; +public: + SurfaceComposerClient(); + virtual ~SurfaceComposerClient(); + + // Always make sure we could initialize + status_t initCheck() const; + + // Return the connection of this client + sp connection() const; + + // Forcibly remove connection before all references have gone away. + void dispose(); + + // callback when the composer is dies + status_t linkToComposerDeath(const sp& recipient, + void* cookie = NULL, uint32_t flags = 0); + + // Get a list of supported configurations for a given display + static status_t getDisplayConfigs(const sp& display, + Vector* configs); + + // Get the DisplayInfo for the currently-active configuration + static status_t getDisplayInfo(const sp& display, + DisplayInfo* info); + + // Get the index of the current active configuration (relative to the list + // returned by getDisplayInfo) + static int getActiveConfig(const sp& display); + + // Set a new active configuration using an index relative to the list + // returned by getDisplayInfo + static status_t setActiveConfig(const sp& display, int id); + + /* Triggers screen on/off or low power mode and waits for it to complete */ + static void setDisplayPowerMode(const sp& display, int mode); + + // ------------------------------------------------------------------------ + // surface creation / destruction + + //! Create a surface + sp createSurface( + const String8& name,// name of the surface + uint32_t w, // width in pixel + uint32_t h, // height in pixel + PixelFormat format, // pixel-format desired + uint32_t flags = 0 // usage flags + ); + + //! Create a virtual display + static sp createDisplay(const String8& displayName, bool secure); + + //! Destroy a virtual display + static void destroyDisplay(const sp& display); + + //! Get the token for the existing default displays. + //! Possible values for id are eDisplayIdMain and eDisplayIdHdmi. + static sp getBuiltInDisplay(int32_t id); + + // ------------------------------------------------------------------------ + // Composer parameters + // All composer parameters must be changed within a transaction + // several surfaces can be updated in one transaction, all changes are + // committed at once when the transaction is closed. + // closeGlobalTransaction() requires an IPC with the server. + + //! Open a composer transaction on all active SurfaceComposerClients. + static void openGlobalTransaction(); + + //! Close a composer transaction on all active SurfaceComposerClients. + static void closeGlobalTransaction(bool synchronous = false); + + //! Flag the currently open transaction as an animation transaction. + static void setAnimationTransaction(); + + status_t hide(const sp& id); + status_t show(const sp& id); + status_t setFlags(const sp& id, uint32_t flags, uint32_t mask); + status_t setTransparentRegionHint(const sp& id, const Region& transparent); + status_t setLayer(const sp& id, uint32_t layer); + status_t setAlpha(const sp& id, float alpha=1.0f); + status_t setMatrix(const sp& id, float dsdx, float dtdx, float dsdy, float dtdy); + status_t setPosition(const sp& id, float x, float y); + status_t setSize(const sp& id, uint32_t w, uint32_t h); + status_t setCrop(const sp& id, const Rect& crop); + status_t setLayerStack(const sp& id, uint32_t layerStack); + status_t destroySurface(const sp& id); + + status_t clearLayerFrameStats(const sp& token) const; + status_t getLayerFrameStats(const sp& token, FrameStats* outStats) const; + + static status_t clearAnimationFrameStats(); + static status_t getAnimationFrameStats(FrameStats* outStats); + + static void setDisplaySurface(const sp& token, + const sp& bufferProducer); + static void setDisplayLayerStack(const sp& token, + uint32_t layerStack); + static void setDisplaySize(const sp& token, uint32_t width, uint32_t height); + + /* setDisplayProjection() defines the projection of layer stacks + * to a given display. + * + * - orientation defines the display's orientation. + * - layerStackRect defines which area of the window manager coordinate + * space will be used. + * - displayRect defines where on the display will layerStackRect be + * mapped to. displayRect is specified post-orientation, that is + * it uses the orientation seen by the end-user. + */ + static void setDisplayProjection(const sp& token, + uint32_t orientation, + const Rect& layerStackRect, + const Rect& displayRect); + + status_t setBlur(const sp& id, float blur); + status_t setBlurMaskSurface(const sp& id, const sp& maskSurfaceId); + status_t setBlurMaskSampling(const sp& id, uint32_t blurMaskSampling); + status_t setBlurMaskAlphaThreshold(const sp& id, float alpha); + +private: + virtual void onFirstRef(); + Composer& getComposer(); + + mutable Mutex mLock; + status_t mStatus; + sp mClient; + Composer& mComposer; +}; + +// --------------------------------------------------------------------------- + +class ScreenshotClient +{ +public: + // if cropping isn't required, callers may pass in a default Rect, e.g.: + // capture(display, producer, Rect(), reqWidth, ...); + static status_t capture( + const sp& display, + const sp& producer, + Rect sourceCrop, uint32_t reqWidth, uint32_t reqHeight, + uint32_t minLayerZ, uint32_t maxLayerZ, + bool useIdentityTransform); + +private: + mutable sp mCpuConsumer; + mutable sp mProducer; + CpuConsumer::LockedBuffer mBuffer; + bool mHaveBuffer; + +public: + ScreenshotClient(); + ~ScreenshotClient(); + + // frees the previous screenshot and captures a new one + // if cropping isn't required, callers may pass in a default Rect, e.g.: + // update(display, Rect(), useIdentityTransform); + status_t update(const sp& display, + Rect sourceCrop, bool useIdentityTransform); + status_t update(const sp& display, + Rect sourceCrop, uint32_t reqWidth, uint32_t reqHeight, + bool useIdentityTransform); + status_t update(const sp& display, + Rect sourceCrop, uint32_t reqWidth, uint32_t reqHeight, + uint32_t minLayerZ, uint32_t maxLayerZ, + bool useIdentityTransform); + status_t update(const sp& display, + Rect sourceCrop, uint32_t reqWidth, uint32_t reqHeight, + uint32_t minLayerZ, uint32_t maxLayerZ, + bool useIdentityTransform, uint32_t rotation); + + sp getCpuConsumer() const; + + // release memory occupied by the screenshot + void release(); + + // pixels are valid until this object is freed or + // release() or update() is called + void const* getPixels() const; + + uint32_t getWidth() const; + uint32_t getHeight() const; + PixelFormat getFormat() const; + uint32_t getStride() const; + // size of allocated memory in bytes + size_t getSize() const; +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_GUI_SURFACE_COMPOSER_CLIENT_H diff --git a/third_party/android_frameworks_native/include/gui/SurfaceControl.h b/third_party/android_frameworks_native/include/gui/SurfaceControl.h new file mode 100644 index 00000000000000..5fa45d1668b9cf --- /dev/null +++ b/third_party/android_frameworks_native/include/gui/SurfaceControl.h @@ -0,0 +1,112 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GUI_SURFACE_CONTROL_H +#define ANDROID_GUI_SURFACE_CONTROL_H + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include + +namespace android { + +// --------------------------------------------------------------------------- + +class IGraphicBufferProducer; +class Surface; +class SurfaceComposerClient; + +// --------------------------------------------------------------------------- + +class SurfaceControl : public RefBase +{ +public: + static bool isValid(const sp& surface) { + return (surface != 0) && surface->isValid(); + } + + bool isValid() { + return mHandle!=0 && mClient!=0; + } + + static bool isSameSurface( + const sp& lhs, const sp& rhs); + + // release surface data from java + void clear(); + + status_t setLayerStack(uint32_t layerStack); + status_t setLayer(uint32_t layer); + status_t setPosition(float x, float y); + status_t setSize(uint32_t w, uint32_t h); + status_t hide(); + status_t show(); + status_t setFlags(uint32_t flags, uint32_t mask); + status_t setTransparentRegionHint(const Region& transparent); + status_t setAlpha(float alpha=1.0f); + status_t setMatrix(float dsdx, float dtdx, float dsdy, float dtdy); + status_t setCrop(const Rect& crop); + + static status_t writeSurfaceToParcel( + const sp& control, Parcel* parcel); + + sp getSurface() const; + + status_t clearLayerFrameStats() const; + status_t getLayerFrameStats(FrameStats* outStats) const; + + status_t setBlur(float blur = 0); + status_t setBlurMaskSurface(const sp& maskSurface); + status_t setBlurMaskSampling(uint32_t blurMaskSampling); + status_t setBlurMaskAlphaThreshold(float alpha); + +private: + // can't be copied + SurfaceControl& operator = (SurfaceControl& rhs); + SurfaceControl(const SurfaceControl& rhs); + + friend class SurfaceComposerClient; + friend class Surface; + + SurfaceControl( + const sp& client, + const sp& handle, + const sp& gbp); + + ~SurfaceControl(); + + status_t validate() const; + void destroy(); + + sp mClient; + sp mHandle; + sp mGraphicBufferProducer; + mutable Mutex mLock; + mutable sp mSurfaceData; +}; + +}; // namespace android + +#endif // ANDROID_GUI_SURFACE_CONTROL_H diff --git a/third_party/android_frameworks_native/include/ui/ANativeObjectBase.h b/third_party/android_frameworks_native/include/ui/ANativeObjectBase.h new file mode 100644 index 00000000000000..76e850fa279aba --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/ANativeObjectBase.h @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_ANDROID_NATIVES_H +#define ANDROID_ANDROID_NATIVES_H + +#include +#include + +#include +#include + +// --------------------------------------------------------------------------- + +/* FIXME: this is legacy for pixmaps */ +typedef struct egl_native_pixmap_t +{ + int32_t version; /* must be 32 */ + int32_t width; + int32_t height; + int32_t stride; + uint8_t* data; + uint8_t format; + uint8_t rfu[3]; + union { + uint32_t compressedFormat; + int32_t vstride; + }; + int32_t reserved; +} egl_native_pixmap_t; + +/*****************************************************************************/ + +#ifdef __cplusplus + +#include + +namespace android { + +/* + * This helper class turns a ANativeXXX object type into a C++ + * reference-counted object; with proper type conversions. + */ +template +class ANativeObjectBase : public NATIVE_TYPE, public REF +{ +public: + // Disambiguate between the incStrong in REF and NATIVE_TYPE + void incStrong(const void* id) const { + REF::incStrong(id); + } + void decStrong(const void* id) const { + REF::decStrong(id); + } + +protected: + typedef ANativeObjectBase BASE; + ANativeObjectBase() : NATIVE_TYPE(), REF() { + NATIVE_TYPE::common.incRef = incRef; + NATIVE_TYPE::common.decRef = decRef; + } + static inline TYPE* getSelf(NATIVE_TYPE* self) { + return static_cast(self); + } + static inline TYPE const* getSelf(NATIVE_TYPE const* self) { + return static_cast(self); + } + static inline TYPE* getSelf(android_native_base_t* base) { + return getSelf(reinterpret_cast(base)); + } + static inline TYPE const * getSelf(android_native_base_t const* base) { + return getSelf(reinterpret_cast(base)); + } + static void incRef(android_native_base_t* base) { + ANativeObjectBase* self = getSelf(base); + self->incStrong(self); + } + static void decRef(android_native_base_t* base) { + ANativeObjectBase* self = getSelf(base); + self->decStrong(self); + } +}; + +} // namespace android +#endif // __cplusplus + +/*****************************************************************************/ + +#endif /* ANDROID_ANDROID_NATIVES_H */ diff --git a/third_party/android_frameworks_native/include/ui/DisplayInfo.h b/third_party/android_frameworks_native/include/ui/DisplayInfo.h new file mode 100644 index 00000000000000..ad73ee72f98063 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/DisplayInfo.h @@ -0,0 +1,52 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_DISPLAY_INFO_H +#define ANDROID_UI_DISPLAY_INFO_H + +#include +#include +#include + +#include + +namespace android { + +struct DisplayInfo { + uint32_t w; + uint32_t h; + float xdpi; + float ydpi; + float fps; + float density; + uint8_t orientation; + bool secure; + nsecs_t appVsyncOffset; + nsecs_t presentationDeadline; + int colorTransform; +}; + +/* Display orientations as defined in Surface.java and ISurfaceComposer.h. */ +enum { + DISPLAY_ORIENTATION_0 = 0, + DISPLAY_ORIENTATION_90 = 1, + DISPLAY_ORIENTATION_180 = 2, + DISPLAY_ORIENTATION_270 = 3 +}; + +}; // namespace android + +#endif // ANDROID_COMPOSER_DISPLAY_INFO_H diff --git a/third_party/android_frameworks_native/include/ui/DisplayStatInfo.h b/third_party/android_frameworks_native/include/ui/DisplayStatInfo.h new file mode 100644 index 00000000000000..0549a832b5274c --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/DisplayStatInfo.h @@ -0,0 +1,31 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_DISPLAY_STAT_INFO_H +#define ANDROID_UI_DISPLAY_STAT_INFO_H + +#include + +namespace android { + +struct DisplayStatInfo { + nsecs_t vsyncTime; + nsecs_t vsyncPeriod; +}; + +}; // namespace android + +#endif // ANDROID_COMPOSER_DISPLAY_STAT_INFO_H diff --git a/third_party/android_frameworks_native/include/ui/Fence.h b/third_party/android_frameworks_native/include/ui/Fence.h new file mode 100644 index 00000000000000..b431bd52aa18fd --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/Fence.h @@ -0,0 +1,117 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_FENCE_H +#define ANDROID_FENCE_H + +#include +#include + +#include +#include +#include +#include +#include +#include + +struct ANativeWindowBuffer; + +namespace android { + +// =========================================================================== +// Fence +// =========================================================================== + +class Fence + : public LightRefBase, public Flattenable +{ +public: + static const sp NO_FENCE; + + // TIMEOUT_NEVER may be passed to the wait method to indicate that it + // should wait indefinitely for the fence to signal. + enum { TIMEOUT_NEVER = -1 }; + + // Construct a new Fence object with an invalid file descriptor. This + // should be done when the Fence object will be set up by unflattening + // serialized data. + Fence(); + + // Construct a new Fence object to manage a given fence file descriptor. + // When the new Fence object is destructed the file descriptor will be + // closed. + Fence(int fenceFd); + + // Check whether the Fence has an open fence file descriptor. Most Fence + // methods treat an invalid file descriptor just like a valid fence that + // is already signalled, so using this is usually not necessary. + bool isValid() const { return mFenceFd != -1; } + + // wait waits for up to timeout milliseconds for the fence to signal. If + // the fence signals then NO_ERROR is returned. If the timeout expires + // before the fence signals then -ETIME is returned. A timeout of + // TIMEOUT_NEVER may be used to indicate that the call should wait + // indefinitely for the fence to signal. + status_t wait(int timeout); + + // waitForever is a convenience function for waiting forever for a fence to + // signal (just like wait(TIMEOUT_NEVER)), but issuing an error to the + // system log and fence state to the kernel log if the wait lasts longer + // than a warning timeout. + // The logname argument should be a string identifying + // the caller and will be included in the log message. + status_t waitForever(const char* logname); + + // merge combines two Fence objects, creating a new Fence object that + // becomes signaled when both f1 and f2 are signaled (even if f1 or f2 is + // destroyed before it becomes signaled). The name argument specifies the + // human-readable name to associated with the new Fence object. + static sp merge(const String8& name, const sp& f1, + const sp& f2); + + // Return a duplicate of the fence file descriptor. The caller is + // responsible for closing the returned file descriptor. On error, -1 will + // be returned and errno will indicate the problem. + int dup() const; + + // getSignalTime returns the system monotonic clock time at which the + // fence transitioned to the signaled state. If the fence is not signaled + // then INT64_MAX is returned. If the fence is invalid or if an error + // occurs then -1 is returned. + nsecs_t getSignalTime() const; + + // Flattenable interface + size_t getFlattenedSize() const; + size_t getFdCount() const; + status_t flatten(void*& buffer, size_t& size, int*& fds, size_t& count) const; + status_t unflatten(void const*& buffer, size_t& size, int const*& fds, size_t& count); + +private: + // Only allow instantiation using ref counting. + friend class LightRefBase; + ~Fence(); + + // Disallow copying + Fence(const Fence& rhs); + Fence& operator = (const Fence& rhs); + const Fence& operator = (const Fence& rhs) const; + + int mFenceFd; +}; + +}; // namespace android + +#endif // ANDROID_FENCE_H diff --git a/third_party/android_frameworks_native/include/ui/FrameStats.h b/third_party/android_frameworks_native/include/ui/FrameStats.h new file mode 100644 index 00000000000000..6bfe635c726304 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/FrameStats.h @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_FRAME_STATS_H +#define ANDROID_UI_FRAME_STATS_H + +#include +#include +#include + +namespace android { + +class FrameStats : public LightFlattenable { +public: + FrameStats() : refreshPeriodNano(0) {}; + + /* + * Approximate refresh time, in nanoseconds. + */ + nsecs_t refreshPeriodNano; + + /* + * The times in nanoseconds for when the frame contents were posted by the producer (e.g. + * the application). They are either explicitly set or defaulted to the time when + * Surface::queueBuffer() was called. + */ + Vector desiredPresentTimesNano; + + /* + * The times in milliseconds for when the frame contents were presented on the screen. + */ + Vector actualPresentTimesNano; + + /* + * The times in nanoseconds for when the frame contents were ready to be presented. Note that + * a frame can be posted and still it contents being rendered asynchronously in GL. In such a + * case these are the times when the frame contents were completely rendered (i.e. their fences + * signaled). + */ + Vector frameReadyTimesNano; + + // LightFlattenable + bool isFixedSize() const; + size_t getFlattenedSize() const; + status_t flatten(void* buffer, size_t size) const; + status_t unflatten(void const* buffer, size_t size); +}; + +}; // namespace android + +#endif // ANDROID_UI_FRAME_STATS_H diff --git a/third_party/android_frameworks_native/include/ui/FramebufferNativeWindow.h b/third_party/android_frameworks_native/include/ui/FramebufferNativeWindow.h new file mode 100644 index 00000000000000..6b66d5f66b0284 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/FramebufferNativeWindow.h @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef INCLUDED_FROM_FRAMEBUFFER_NATIVE_WINDOW_CPP +#warning "FramebufferNativeWindow is deprecated" +#endif + +#ifndef ANDROID_FRAMEBUFFER_NATIVE_WINDOW_H +#define ANDROID_FRAMEBUFFER_NATIVE_WINDOW_H + +#include +#include + +#include + +#include +#include + +#include +#include + +#define MIN_NUM_FRAME_BUFFERS 2 +#define MAX_NUM_FRAME_BUFFERS 3 + +extern "C" EGLNativeWindowType android_createDisplaySurface(void); + +// --------------------------------------------------------------------------- +namespace android { +// --------------------------------------------------------------------------- + +class Surface; +class NativeBuffer; + +// --------------------------------------------------------------------------- + +class FramebufferNativeWindow + : public ANativeObjectBase< + ANativeWindow, + FramebufferNativeWindow, + LightRefBase > +{ +public: + FramebufferNativeWindow(); + + framebuffer_device_t const * getDevice() const { return fbDev; } + + bool isUpdateOnDemand() const { return mUpdateOnDemand; } + status_t setUpdateRectangle(const Rect& updateRect); + status_t compositionComplete(); + + void dump(String8& result); + + // for debugging only + int getCurrentBufferIndex() const; + +private: + friend class LightRefBase; + ~FramebufferNativeWindow(); // this class cannot be overloaded + static int setSwapInterval(ANativeWindow* window, int interval); + static int dequeueBuffer(ANativeWindow* window, ANativeWindowBuffer** buffer, int* fenceFd); + static int queueBuffer(ANativeWindow* window, ANativeWindowBuffer* buffer, int fenceFd); + static int query(const ANativeWindow* window, int what, int* value); + static int perform(ANativeWindow* window, int operation, ...); + + static int dequeueBuffer_DEPRECATED(ANativeWindow* window, ANativeWindowBuffer** buffer); + static int queueBuffer_DEPRECATED(ANativeWindow* window, ANativeWindowBuffer* buffer); + static int lockBuffer_DEPRECATED(ANativeWindow* window, ANativeWindowBuffer* buffer); + + framebuffer_device_t* fbDev; + alloc_device_t* grDev; + + sp buffers[MAX_NUM_FRAME_BUFFERS]; + sp front; + + mutable Mutex mutex; + Condition mCondition; + int32_t mNumBuffers; + int32_t mNumFreeBuffers; + int32_t mBufferHead; + int32_t mCurrentBufferIndex; + bool mUpdateOnDemand; +}; + +// --------------------------------------------------------------------------- +}; // namespace android +// --------------------------------------------------------------------------- + +#endif // ANDROID_FRAMEBUFFER_NATIVE_WINDOW_H + diff --git a/third_party/android_frameworks_native/include/ui/GraphicBuffer.h b/third_party/android_frameworks_native/include/ui/GraphicBuffer.h new file mode 100644 index 00000000000000..3da720ff376c69 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/GraphicBuffer.h @@ -0,0 +1,183 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_GRAPHIC_BUFFER_H +#define ANDROID_GRAPHIC_BUFFER_H + +#include +#include + +#include +#include +#include +#include +#include + + +struct ANativeWindowBuffer; + +namespace android { + +class GraphicBufferMapper; + +// =========================================================================== +// GraphicBuffer +// =========================================================================== + +class GraphicBuffer + : public ANativeObjectBase< ANativeWindowBuffer, GraphicBuffer, RefBase >, + public Flattenable +{ + friend class Flattenable; +public: + + enum { + USAGE_SW_READ_NEVER = GRALLOC_USAGE_SW_READ_NEVER, + USAGE_SW_READ_RARELY = GRALLOC_USAGE_SW_READ_RARELY, + USAGE_SW_READ_OFTEN = GRALLOC_USAGE_SW_READ_OFTEN, + USAGE_SW_READ_MASK = GRALLOC_USAGE_SW_READ_MASK, + + USAGE_SW_WRITE_NEVER = GRALLOC_USAGE_SW_WRITE_NEVER, + USAGE_SW_WRITE_RARELY = GRALLOC_USAGE_SW_WRITE_RARELY, + USAGE_SW_WRITE_OFTEN = GRALLOC_USAGE_SW_WRITE_OFTEN, + USAGE_SW_WRITE_MASK = GRALLOC_USAGE_SW_WRITE_MASK, + + USAGE_SOFTWARE_MASK = USAGE_SW_READ_MASK|USAGE_SW_WRITE_MASK, + + USAGE_PROTECTED = GRALLOC_USAGE_PROTECTED, + + USAGE_HW_TEXTURE = GRALLOC_USAGE_HW_TEXTURE, + USAGE_HW_RENDER = GRALLOC_USAGE_HW_RENDER, + USAGE_HW_2D = GRALLOC_USAGE_HW_2D, + USAGE_HW_COMPOSER = GRALLOC_USAGE_HW_COMPOSER, + USAGE_HW_VIDEO_ENCODER = GRALLOC_USAGE_HW_VIDEO_ENCODER, + USAGE_HW_MASK = GRALLOC_USAGE_HW_MASK, + + USAGE_CURSOR = GRALLOC_USAGE_CURSOR, + }; + + GraphicBuffer(); + + // creates w * h buffer + GraphicBuffer(uint32_t inWidth, uint32_t inHeight, PixelFormat inFormat, + uint32_t inUsage); + + // create a buffer from an existing handle + GraphicBuffer(uint32_t inWidth, uint32_t inHeight, PixelFormat inFormat, + uint32_t inUsage, uint32_t inStride, native_handle_t* inHandle, + bool keepOwnership); + + // create a buffer from an existing ANativeWindowBuffer + GraphicBuffer(ANativeWindowBuffer* buffer, bool keepOwnership); + + // return status + status_t initCheck() const; + + uint32_t getWidth() const { return static_cast(width); } + uint32_t getHeight() const { return static_cast(height); } + uint32_t getStride() const { return static_cast(stride); } + uint32_t getUsage() const { return static_cast(usage); } + PixelFormat getPixelFormat() const { return format; } + Rect getBounds() const { return Rect(width, height); } + uint64_t getId() const { return mId; } + + uint32_t getGenerationNumber() const { return mGenerationNumber; } + void setGenerationNumber(uint32_t generation) { + mGenerationNumber = generation; + } + + status_t reallocate(uint32_t inWidth, uint32_t inHeight, + PixelFormat inFormat, uint32_t inUsage); + + bool needsReallocation(uint32_t inWidth, uint32_t inHeight, + PixelFormat inFormat, uint32_t inUsage); + + status_t lock(uint32_t inUsage, void** vaddr); + status_t lock(uint32_t inUsage, const Rect& rect, void** vaddr); + // For HAL_PIXEL_FORMAT_YCbCr_420_888 + status_t lockYCbCr(uint32_t inUsage, android_ycbcr *ycbcr); + status_t lockYCbCr(uint32_t inUsage, const Rect& rect, + android_ycbcr *ycbcr); + status_t unlock(); + status_t lockAsync(uint32_t inUsage, void** vaddr, int fenceFd); + status_t lockAsync(uint32_t inUsage, const Rect& rect, void** vaddr, + int fenceFd); + status_t lockAsyncYCbCr(uint32_t inUsage, android_ycbcr *ycbcr, + int fenceFd); + status_t lockAsyncYCbCr(uint32_t inUsage, const Rect& rect, + android_ycbcr *ycbcr, int fenceFd); + status_t unlockAsync(int *fenceFd); + + ANativeWindowBuffer* getNativeBuffer() const; + + // for debugging + static void dumpAllocationsToSystemLog(); + + // Flattenable protocol + size_t getFlattenedSize() const; + size_t getFdCount() const; + status_t flatten(void*& buffer, size_t& size, int*& fds, size_t& count) const; + status_t unflatten(void const*& buffer, size_t& size, int const*& fds, size_t& count); + +private: + ~GraphicBuffer(); + + enum { + ownNone = 0, + ownHandle = 1, + ownData = 2, + }; + + inline const GraphicBufferMapper& getBufferMapper() const { + return mBufferMapper; + } + inline GraphicBufferMapper& getBufferMapper() { + return mBufferMapper; + } + uint8_t mOwner; + +private: + friend class Surface; + friend class BpSurface; + friend class BnSurface; + friend class LightRefBase; + GraphicBuffer(const GraphicBuffer& rhs); + GraphicBuffer& operator = (const GraphicBuffer& rhs); + const GraphicBuffer& operator = (const GraphicBuffer& rhs) const; + + status_t initSize(uint32_t inWidth, uint32_t inHeight, PixelFormat inFormat, + uint32_t inUsage); + + void free_handle(); + + GraphicBufferMapper& mBufferMapper; + ssize_t mInitCheck; + + // If we're wrapping another buffer then this reference will make sure it + // doesn't get freed. + sp mWrappedBuffer; + + uint64_t mId; + + // Stores the generation number of this buffer. If this number does not + // match the BufferQueue's internal generation number (set through + // IGBP::setGenerationNumber), attempts to attach the buffer will fail. + uint32_t mGenerationNumber; +}; + +}; // namespace android + +#endif // ANDROID_GRAPHIC_BUFFER_H diff --git a/third_party/android_frameworks_native/include/ui/GraphicBufferAllocator.h b/third_party/android_frameworks_native/include/ui/GraphicBufferAllocator.h new file mode 100644 index 00000000000000..5443f09a104d6c --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/GraphicBufferAllocator.h @@ -0,0 +1,95 @@ +/* +** +** Copyright 2009, The Android Open Source Project +** +** Licensed under the Apache License, Version 2.0 (the "License"); +** you may not use this file except in compliance with the License. +** You may obtain a copy of the License at +** +** http://www.apache.org/licenses/LICENSE-2.0 +** +** Unless required by applicable law or agreed to in writing, software +** distributed under the License is distributed on an "AS IS" BASIS, +** WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +** See the License for the specific language governing permissions and +** limitations under the License. +*/ + +#ifndef ANDROID_BUFFER_ALLOCATOR_H +#define ANDROID_BUFFER_ALLOCATOR_H + +#include + +#include + +#include +#include +#include +#include + +#include + +#include + + +namespace android { +// --------------------------------------------------------------------------- + +class String8; + +class GraphicBufferAllocator : public Singleton +{ +public: + enum { + USAGE_SW_READ_NEVER = GRALLOC_USAGE_SW_READ_NEVER, + USAGE_SW_READ_RARELY = GRALLOC_USAGE_SW_READ_RARELY, + USAGE_SW_READ_OFTEN = GRALLOC_USAGE_SW_READ_OFTEN, + USAGE_SW_READ_MASK = GRALLOC_USAGE_SW_READ_MASK, + + USAGE_SW_WRITE_NEVER = GRALLOC_USAGE_SW_WRITE_NEVER, + USAGE_SW_WRITE_RARELY = GRALLOC_USAGE_SW_WRITE_RARELY, + USAGE_SW_WRITE_OFTEN = GRALLOC_USAGE_SW_WRITE_OFTEN, + USAGE_SW_WRITE_MASK = GRALLOC_USAGE_SW_WRITE_MASK, + + USAGE_SOFTWARE_MASK = USAGE_SW_READ_MASK|USAGE_SW_WRITE_MASK, + + USAGE_HW_TEXTURE = GRALLOC_USAGE_HW_TEXTURE, + USAGE_HW_RENDER = GRALLOC_USAGE_HW_RENDER, + USAGE_HW_2D = GRALLOC_USAGE_HW_2D, + USAGE_HW_MASK = GRALLOC_USAGE_HW_MASK + }; + + static inline GraphicBufferAllocator& get() { return getInstance(); } + + status_t alloc(uint32_t w, uint32_t h, PixelFormat format, uint32_t usage, + buffer_handle_t* handle, uint32_t* stride); + + status_t free(buffer_handle_t handle); + + void dump(String8& res) const; + static void dumpToSystemLog(); + +private: + struct alloc_rec_t { + uint32_t width; + uint32_t height; + uint32_t stride; + PixelFormat format; + uint32_t usage; + size_t size; + }; + + static Mutex sLock; + static KeyedVector sAllocList; + + friend class Singleton; + GraphicBufferAllocator(); + ~GraphicBufferAllocator(); + + alloc_device_t *mAllocDev; +}; + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_BUFFER_ALLOCATOR_H diff --git a/third_party/android_frameworks_native/include/ui/GraphicBufferMapper.h b/third_party/android_frameworks_native/include/ui/GraphicBufferMapper.h new file mode 100644 index 00000000000000..99006248275828 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/GraphicBufferMapper.h @@ -0,0 +1,80 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_BUFFER_MAPPER_H +#define ANDROID_UI_BUFFER_MAPPER_H + +#include +#include + +#include + +#include + + +struct gralloc_module_t; + +namespace android { + +// --------------------------------------------------------------------------- + +class Rect; + +class GraphicBufferMapper : public Singleton +{ +public: + static inline GraphicBufferMapper& get() { return getInstance(); } + + status_t registerBuffer(buffer_handle_t handle); + + status_t unregisterBuffer(buffer_handle_t handle); + + status_t lock(buffer_handle_t handle, + uint32_t usage, const Rect& bounds, void** vaddr); + + status_t lockYCbCr(buffer_handle_t handle, + uint32_t usage, const Rect& bounds, android_ycbcr *ycbcr); + + status_t unlock(buffer_handle_t handle); + + status_t lockAsync(buffer_handle_t handle, + uint32_t usage, const Rect& bounds, void** vaddr, int fenceFd); + + status_t lockAsyncYCbCr(buffer_handle_t handle, + uint32_t usage, const Rect& bounds, android_ycbcr *ycbcr, + int fenceFd); + + status_t unlockAsync(buffer_handle_t handle, int *fenceFd); + +#ifdef EXYNOS4_ENHANCEMENTS + status_t getphys(buffer_handle_t handle, void** paddr); +#endif + + // dumps information about the mapping of this handle + void dump(buffer_handle_t handle); + +private: + friend class Singleton; + GraphicBufferMapper(); + gralloc_module_t const *mAllocMod; +}; + +// --------------------------------------------------------------------------- + +}; // namespace android + +#endif // ANDROID_UI_BUFFER_MAPPER_H + diff --git a/third_party/android_frameworks_native/include/ui/PixelFormat.h b/third_party/android_frameworks_native/include/ui/PixelFormat.h new file mode 100644 index 00000000000000..f26fecb8b14709 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/PixelFormat.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// + +// Pixel formats used across the system. +// These formats might not all be supported by all renderers, for instance +// skia or SurfaceFlinger are not required to support all of these formats +// (either as source or destination) + + +#ifndef UI_PIXELFORMAT_H +#define UI_PIXELFORMAT_H + +#include + +namespace android { + +enum { + // + // these constants need to match those + // in graphics/PixelFormat.java & pixelflinger/format.h + // + PIXEL_FORMAT_UNKNOWN = 0, + PIXEL_FORMAT_NONE = 0, + + // logical pixel formats used by the SurfaceFlinger ----------------------- + PIXEL_FORMAT_CUSTOM = -4, + // Custom pixel-format described by a PixelFormatInfo structure + + PIXEL_FORMAT_TRANSLUCENT = -3, + // System chooses a format that supports translucency (many alpha bits) + + PIXEL_FORMAT_TRANSPARENT = -2, + // System chooses a format that supports transparency + // (at least 1 alpha bit) + + PIXEL_FORMAT_OPAQUE = -1, + // System chooses an opaque format (no alpha bits required) + + // real pixel formats supported for rendering ----------------------------- + + PIXEL_FORMAT_RGBA_8888 = HAL_PIXEL_FORMAT_RGBA_8888, // 4x8-bit RGBA + PIXEL_FORMAT_RGBX_8888 = HAL_PIXEL_FORMAT_RGBX_8888, // 4x8-bit RGB0 + PIXEL_FORMAT_RGB_888 = HAL_PIXEL_FORMAT_RGB_888, // 3x8-bit RGB + PIXEL_FORMAT_RGB_565 = HAL_PIXEL_FORMAT_RGB_565, // 16-bit RGB + PIXEL_FORMAT_BGRA_8888 = HAL_PIXEL_FORMAT_BGRA_8888, // 4x8-bit BGRA + PIXEL_FORMAT_RGBA_5551 = 6, // 16-bit ARGB + PIXEL_FORMAT_RGBA_4444 = 7, // 16-bit ARGB +}; + +typedef int32_t PixelFormat; + +uint32_t bytesPerPixel(PixelFormat format); +uint32_t bitsPerPixel(PixelFormat format); + +}; // namespace android + +#endif // UI_PIXELFORMAT_H diff --git a/third_party/android_frameworks_native/include/ui/Point.h b/third_party/android_frameworks_native/include/ui/Point.h new file mode 100644 index 00000000000000..1d7f64d30732c0 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/Point.h @@ -0,0 +1,88 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_POINT +#define ANDROID_UI_POINT + +#include +#include + +namespace android { + +class Point : public LightFlattenablePod +{ +public: + int x; + int y; + + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + // Default constructor doesn't initialize the Point + inline Point() { + } + inline Point(int x, int y) : x(x), y(y) { + } + + inline bool operator == (const Point& rhs) const { + return (x == rhs.x) && (y == rhs.y); + } + inline bool operator != (const Point& rhs) const { + return !operator == (rhs); + } + + inline bool isOrigin() const { + return !(x|y); + } + + // operator < defines an order which allows to use points in sorted + // vectors. + bool operator < (const Point& rhs) const { + return y +#include +#include +#include + +#include + +namespace android { + +class Rect : public ARect, public LightFlattenablePod +{ +public: + typedef ARect::value_type value_type; + + static const Rect INVALID_RECT; + + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + inline Rect() { + left = right = top = bottom = 0; + } + + inline Rect(int32_t w, int32_t h) { + left = top = 0; + right = w; + bottom = h; + } + + inline Rect(uint32_t w, uint32_t h) { + if (w > INT32_MAX) { + ALOG(LOG_WARN, "Rect", + "Width %u too large for Rect class, clamping", w); + w = INT32_MAX; + } + if (h > INT32_MAX) { + ALOG(LOG_WARN, "Rect", + "Height %u too large for Rect class, clamping", h); + h = INT32_MAX; + } + left = top = 0; + right = w; + bottom = h; + } + + inline Rect(int32_t l, int32_t t, int32_t r, int32_t b) { + left = l; + top = t; + right = r; + bottom = b; + } + + inline Rect(const Point& lt, const Point& rb) { + left = lt.x; + top = lt.y; + right = rb.x; + bottom = rb.y; + } + + void makeInvalid(); + + inline void clear() { + left = top = right = bottom = 0; + } + + // a valid rectangle has a non negative width and height + inline bool isValid() const { + return (getWidth() >= 0) && (getHeight() >= 0); + } + + // an empty rect has a zero width or height, or is invalid + inline bool isEmpty() const { + return (getWidth() <= 0) || (getHeight() <= 0); + } + + // rectangle's width + inline int32_t getWidth() const { + return right - left; + } + + // rectangle's height + inline int32_t getHeight() const { + return bottom - top; + } + + inline Rect getBounds() const { + return Rect(right - left, bottom - top); + } + + void setLeftTop(const Point& lt) { + left = lt.x; + top = lt.y; + } + + void setRightBottom(const Point& rb) { + right = rb.x; + bottom = rb.y; + } + + // the following 4 functions return the 4 corners of the rect as Point + Point leftTop() const { + return Point(left, top); + } + Point rightBottom() const { + return Point(right, bottom); + } + Point rightTop() const { + return Point(right, top); + } + Point leftBottom() const { + return Point(left, bottom); + } + + // comparisons + inline bool operator == (const Rect& rhs) const { + return (left == rhs.left) && (top == rhs.top) && + (right == rhs.right) && (bottom == rhs.bottom); + } + + inline bool operator != (const Rect& rhs) const { + return !operator == (rhs); + } + + // operator < defines an order which allows to use rectangles in sorted + // vectors. + bool operator < (const Rect& rhs) const; + + const Rect operator + (const Point& rhs) const; + const Rect operator - (const Point& rhs) const; + + Rect& operator += (const Point& rhs) { + return offsetBy(rhs.x, rhs.y); + } + Rect& operator -= (const Point& rhs) { + return offsetBy(-rhs.x, -rhs.y); + } + + Rect& offsetToOrigin() { + right -= left; + bottom -= top; + left = top = 0; + return *this; + } + Rect& offsetTo(const Point& p) { + return offsetTo(p.x, p.y); + } + Rect& offsetBy(const Point& dp) { + return offsetBy(dp.x, dp.y); + } + + Rect& offsetTo(int32_t x, int32_t y); + Rect& offsetBy(int32_t x, int32_t y); + + bool intersect(const Rect& with, Rect* result) const; + + // Create a new Rect by transforming this one using a graphics HAL + // transform. This rectangle is defined in a coordinate space starting at + // the origin and extending to (width, height). If the transform includes + // a ROT90 then the output rectangle is defined in a space extending to + // (height, width). Otherwise the output rectangle is in the same space as + // the input. + Rect transform(uint32_t xform, int32_t width, int32_t height) const; + + // this calculates (Region(*this) - exclude).bounds() efficiently + Rect reduce(const Rect& exclude) const; + + + // for backward compatibility + inline int32_t width() const { return getWidth(); } + inline int32_t height() const { return getHeight(); } + inline void set(const Rect& rhs) { operator = (rhs); } +}; + +ANDROID_BASIC_TYPES_TRAITS(Rect) + +}; // namespace android + +#endif // ANDROID_UI_RECT diff --git a/third_party/android_frameworks_native/include/ui/Region.h b/third_party/android_frameworks_native/include/ui/Region.h new file mode 100644 index 00000000000000..2a1491837dc78e --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/Region.h @@ -0,0 +1,223 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_REGION_H +#define ANDROID_UI_REGION_H + +#include +#include + +#include + +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +class SharedBuffer; +class String8; + +// --------------------------------------------------------------------------- +class Region : public LightFlattenable +{ +public: + static const Region INVALID_REGION; + + Region(); + Region(const Region& rhs); + explicit Region(const Rect& rhs); + ~Region(); + + static Region createTJunctionFreeRegion(const Region& r); + + Region& operator = (const Region& rhs); + + inline bool isEmpty() const { return getBounds().isEmpty(); } + inline bool isRect() const { return mStorage.size() == 1; } + + inline Rect getBounds() const { return mStorage[mStorage.size() - 1]; } + inline Rect bounds() const { return getBounds(); } + + bool contains(const Point& point) const; + bool contains(int x, int y) const; + + // the region becomes its bounds + Region& makeBoundsSelf(); + + void clear(); + void set(const Rect& r); + void set(int32_t w, int32_t h); + void set(uint32_t w, uint32_t h); + + Region& orSelf(const Rect& rhs); + Region& xorSelf(const Rect& rhs); + Region& andSelf(const Rect& rhs); + Region& subtractSelf(const Rect& rhs); + + // boolean operators, applied on this + Region& orSelf(const Region& rhs); + Region& xorSelf(const Region& rhs); + Region& andSelf(const Region& rhs); + Region& subtractSelf(const Region& rhs); + + // boolean operators + const Region merge(const Rect& rhs) const; + const Region mergeExclusive(const Rect& rhs) const; + const Region intersect(const Rect& rhs) const; + const Region subtract(const Rect& rhs) const; + + // boolean operators + const Region merge(const Region& rhs) const; + const Region mergeExclusive(const Region& rhs) const; + const Region intersect(const Region& rhs) const; + const Region subtract(const Region& rhs) const; + + // these translate rhs first + Region& translateSelf(int dx, int dy); + Region& orSelf(const Region& rhs, int dx, int dy); + Region& xorSelf(const Region& rhs, int dx, int dy); + Region& andSelf(const Region& rhs, int dx, int dy); + Region& subtractSelf(const Region& rhs, int dx, int dy); + + // these translate rhs first + const Region translate(int dx, int dy) const; + const Region merge(const Region& rhs, int dx, int dy) const; + const Region mergeExclusive(const Region& rhs, int dx, int dy) const; + const Region intersect(const Region& rhs, int dx, int dy) const; + const Region subtract(const Region& rhs, int dx, int dy) const; + + // convenience operators overloads + inline const Region operator | (const Region& rhs) const; + inline const Region operator ^ (const Region& rhs) const; + inline const Region operator & (const Region& rhs) const; + inline const Region operator - (const Region& rhs) const; + inline const Region operator + (const Point& pt) const; + + inline Region& operator |= (const Region& rhs); + inline Region& operator ^= (const Region& rhs); + inline Region& operator &= (const Region& rhs); + inline Region& operator -= (const Region& rhs); + inline Region& operator += (const Point& pt); + + + // returns true if the regions share the same underlying storage + bool isTriviallyEqual(const Region& region) const; + + + /* various ways to access the rectangle list */ + + + // STL-like iterators + typedef Rect const* const_iterator; + const_iterator begin() const; + const_iterator end() const; + + // returns an array of rect which has the same life-time has this + // Region object. + Rect const* getArray(size_t* count) const; + + // returns a SharedBuffer as well as the number of rects. + // ownership is transfered to the caller. + // the caller must call SharedBuffer::release() to free the memory. + SharedBuffer const* getSharedBuffer(size_t* count) const; + + /* no user serviceable parts here... */ + + // add a rectangle to the internal list. This rectangle must + // be sorted in Y and X and must not make the region invalid. + void addRectUnchecked(int l, int t, int r, int b); + + inline bool isFixedSize() const { return false; } + size_t getFlattenedSize() const; + status_t flatten(void* buffer, size_t size) const; + status_t unflatten(void const* buffer, size_t size); + + void dump(String8& out, const char* what, uint32_t flags=0) const; + void dump(const char* what, uint32_t flags=0) const; + +private: + class rasterizer; + friend class rasterizer; + + Region& operationSelf(const Rect& r, int op); + Region& operationSelf(const Region& r, int op); + Region& operationSelf(const Region& r, int dx, int dy, int op); + const Region operation(const Rect& rhs, int op) const; + const Region operation(const Region& rhs, int op) const; + const Region operation(const Region& rhs, int dx, int dy, int op) const; + + static void boolean_operation(int op, Region& dst, + const Region& lhs, const Region& rhs, int dx, int dy); + static void boolean_operation(int op, Region& dst, + const Region& lhs, const Rect& rhs, int dx, int dy); + + static void boolean_operation(int op, Region& dst, + const Region& lhs, const Region& rhs); + static void boolean_operation(int op, Region& dst, + const Region& lhs, const Rect& rhs); + + static void translate(Region& reg, int dx, int dy); + static void translate(Region& dst, const Region& reg, int dx, int dy); + + static bool validate(const Region& reg, + const char* name, bool silent = false); + + // mStorage is a (manually) sorted array of Rects describing the region + // with an extra Rect as the last element which is set to the + // bounds of the region. However, if the region is + // a simple Rect then mStorage contains only that rect. + Vector mStorage; +}; + + +const Region Region::operator | (const Region& rhs) const { + return merge(rhs); +} +const Region Region::operator ^ (const Region& rhs) const { + return mergeExclusive(rhs); +} +const Region Region::operator & (const Region& rhs) const { + return intersect(rhs); +} +const Region Region::operator - (const Region& rhs) const { + return subtract(rhs); +} +const Region Region::operator + (const Point& pt) const { + return translate(pt.x, pt.y); +} + + +Region& Region::operator |= (const Region& rhs) { + return orSelf(rhs); +} +Region& Region::operator ^= (const Region& rhs) { + return xorSelf(rhs); +} +Region& Region::operator &= (const Region& rhs) { + return andSelf(rhs); +} +Region& Region::operator -= (const Region& rhs) { + return subtractSelf(rhs); +} +Region& Region::operator += (const Point& pt) { + return translateSelf(pt.x, pt.y); +} +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_UI_REGION_H + diff --git a/third_party/android_frameworks_native/include/ui/TMatHelpers.h b/third_party/android_frameworks_native/include/ui/TMatHelpers.h new file mode 100644 index 00000000000000..a6aadcad4096b3 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/TMatHelpers.h @@ -0,0 +1,257 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef TMAT_IMPLEMENTATION +#error "Don't include TMatHelpers.h directly. use ui/mat*.h instead" +#else +#undef TMAT_IMPLEMENTATION +#endif + + +#ifndef UI_TMAT_HELPERS_H +#define UI_TMAT_HELPERS_H + +#include +#include +#include +#include +#include + +#define PURE __attribute__((pure)) + +namespace android { +// ------------------------------------------------------------------------------------- + +/* + * No user serviceable parts here. + * + * Don't use this file directly, instead include ui/mat*.h + */ + + +/* + * Matrix utilities + */ + +namespace matrix { + +inline int PURE transpose(int v) { return v; } +inline float PURE transpose(float v) { return v; } +inline double PURE transpose(double v) { return v; } + +inline int PURE trace(int v) { return v; } +inline float PURE trace(float v) { return v; } +inline double PURE trace(double v) { return v; } + +template +MATRIX PURE inverse(const MATRIX& src) { + + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX::COL_SIZE == MATRIX::ROW_SIZE ); + + typename MATRIX::value_type t; + const size_t N = MATRIX::col_size(); + size_t swap; + MATRIX tmp(src); + MATRIX inverse(1); + + for (size_t i=0 ; i fabs(tmp[i][i])) { + swap = j; + } + } + + if (swap != i) { + /* swap rows. */ + for (size_t k=0 ; k +MATRIX_R PURE multiply(const MATRIX_A& lhs, const MATRIX_B& rhs) { + // pre-requisite: + // lhs : D columns, R rows + // rhs : C columns, D rows + // res : C columns, R rows + + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX_A::ROW_SIZE == MATRIX_B::COL_SIZE ); + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX_R::ROW_SIZE == MATRIX_B::ROW_SIZE ); + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX_R::COL_SIZE == MATRIX_A::COL_SIZE ); + + MATRIX_R res(MATRIX_R::NO_INIT); + for (size_t r=0 ; r +MATRIX PURE transpose(const MATRIX& m) { + // for now we only handle square matrix transpose + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX::ROW_SIZE == MATRIX::COL_SIZE ); + MATRIX result(MATRIX::NO_INIT); + for (size_t r=0 ; r +typename MATRIX::value_type PURE trace(const MATRIX& m) { + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX::ROW_SIZE == MATRIX::COL_SIZE ); + typename MATRIX::value_type result(0); + for (size_t r=0 ; r +typename MATRIX::col_type PURE diag(const MATRIX& m) { + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( MATRIX::ROW_SIZE == MATRIX::COL_SIZE ); + typename MATRIX::col_type result(MATRIX::col_type::NO_INIT); + for (size_t r=0 ; r +String8 asString(const MATRIX& m) { + String8 s; + for (size_t c=0 ; c. + * + * BASE only needs to implement operator[] and size(). + * By simply inheriting from TMatProductOperators BASE will automatically + * get all the functionality here. + */ + +template class BASE, typename T> +class TMatProductOperators { +public: + // multiply by a scalar + BASE& operator *= (T v) { + BASE& lhs(static_cast< BASE& >(*this)); + for (size_t r=0 ; r& operator /= (T v) { + BASE& lhs(static_cast< BASE& >(*this)); + for (size_t r=0 ; r + friend BASE PURE operator *(const BASE& lhs, const BASE& rhs) { + return matrix::multiply >(lhs, rhs); + } +}; + + +/* + * TMatSquareFunctions implements functions on a matrix of type BASE. + * + * BASE only needs to implement: + * - operator[] + * - col_type + * - row_type + * - COL_SIZE + * - ROW_SIZE + * + * By simply inheriting from TMatSquareFunctions BASE will automatically + * get all the functionality here. + */ + +template class BASE, typename T> +class TMatSquareFunctions { +public: + /* + * NOTE: the functions below ARE NOT member methods. They are friend functions + * with they definition inlined with their declaration. This makes these + * template functions available to the compiler when (and only when) this class + * is instantiated, at which point they're only templated on the 2nd parameter + * (the first one, BASE being known). + */ + friend BASE PURE inverse(const BASE& m) { return matrix::inverse(m); } + friend BASE PURE transpose(const BASE& m) { return matrix::transpose(m); } + friend T PURE trace(const BASE& m) { return matrix::trace(m); } +}; + +template class BASE, typename T> +class TMatDebug { +public: + String8 asString() const { + return matrix::asString( static_cast< const BASE& >(*this) ); + } +}; + +// ------------------------------------------------------------------------------------- +}; // namespace android + +#undef PURE + +#endif /* UI_TMAT_HELPERS_H */ diff --git a/third_party/android_frameworks_native/include/ui/TVecHelpers.h b/third_party/android_frameworks_native/include/ui/TVecHelpers.h new file mode 100644 index 00000000000000..bb7dbfc2b893b9 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/TVecHelpers.h @@ -0,0 +1,381 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef TVEC_IMPLEMENTATION +#error "Don't include TVecHelpers.h directly. use ui/vec*.h instead" +#else +#undef TVEC_IMPLEMENTATION +#endif + + +#ifndef UI_TVEC_HELPERS_H +#define UI_TVEC_HELPERS_H + +#include +#include + +#define PURE __attribute__((pure)) + +namespace android { +// ------------------------------------------------------------------------------------- + +/* + * No user serviceable parts here. + * + * Don't use this file directly, instead include ui/vec{2|3|4}.h + */ + +/* + * This class casts itself into anything and assign itself from anything! + * Use with caution! + */ +template +struct Impersonator { + Impersonator& operator = (const TYPE& rhs) { + reinterpret_cast(*this) = rhs; + return *this; + } + operator TYPE& () { + return reinterpret_cast(*this); + } + operator TYPE const& () const { + return reinterpret_cast(*this); + } +}; + +/* + * TVec{Add|Product}Operators implements basic arithmetic and basic compound assignments + * operators on a vector of type BASE. + * + * BASE only needs to implement operator[] and size(). + * By simply inheriting from TVec{Add|Product}Operators BASE will automatically + * get all the functionality here. + */ + +template class BASE, typename T> +class TVecAddOperators { +public: + /* compound assignment from a another vector of the same size but different + * element type. + */ + template + BASE& operator += (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] += v[i]; + } + return rhs; + } + template + BASE& operator -= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] -= v[i]; + } + return rhs; + } + + /* compound assignment from a another vector of the same type. + * These operators can be used for implicit conversion and handle operations + * like "vector *= scalar" by letting the compiler implicitly convert a scalar + * to a vector (assuming the BASE allows it). + */ + BASE& operator += (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] += v[i]; + } + return rhs; + } + BASE& operator -= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] -= v[i]; + } + return rhs; + } + + /* + * NOTE: the functions below ARE NOT member methods. They are friend functions + * with they definition inlined with their declaration. This makes these + * template functions available to the compiler when (and only when) this class + * is instantiated, at which point they're only templated on the 2nd parameter + * (the first one, BASE being known). + */ + + /* The operators below handle operation between vectors of the same side + * but of a different element type. + */ + template + friend inline + BASE PURE operator +(const BASE& lv, const BASE& rv) { + return BASE(lv) += rv; + } + template + friend inline + BASE PURE operator -(const BASE& lv, const BASE& rv) { + return BASE(lv) -= rv; + } + + /* The operators below (which are not templates once this class is instanced, + * i.e.: BASE is known) can be used for implicit conversion on both sides. + * These handle operations like "vector * scalar" and "scalar * vector" by + * letting the compiler implicitly convert a scalar to a vector (assuming + * the BASE allows it). + */ + friend inline + BASE PURE operator +(const BASE& lv, const BASE& rv) { + return BASE(lv) += rv; + } + friend inline + BASE PURE operator -(const BASE& lv, const BASE& rv) { + return BASE(lv) -= rv; + } +}; + +template class BASE, typename T> +class TVecProductOperators { +public: + /* compound assignment from a another vector of the same size but different + * element type. + */ + template + BASE& operator *= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] *= v[i]; + } + return rhs; + } + template + BASE& operator /= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] /= v[i]; + } + return rhs; + } + + /* compound assignment from a another vector of the same type. + * These operators can be used for implicit conversion and handle operations + * like "vector *= scalar" by letting the compiler implicitly convert a scalar + * to a vector (assuming the BASE allows it). + */ + BASE& operator *= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] *= v[i]; + } + return rhs; + } + BASE& operator /= (const BASE& v) { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + rhs[i] /= v[i]; + } + return rhs; + } + + /* + * NOTE: the functions below ARE NOT member methods. They are friend functions + * with they definition inlined with their declaration. This makes these + * template functions available to the compiler when (and only when) this class + * is instantiated, at which point they're only templated on the 2nd parameter + * (the first one, BASE being known). + */ + + /* The operators below handle operation between vectors of the same side + * but of a different element type. + */ + template + friend inline + BASE PURE operator *(const BASE& lv, const BASE& rv) { + return BASE(lv) *= rv; + } + template + friend inline + BASE PURE operator /(const BASE& lv, const BASE& rv) { + return BASE(lv) /= rv; + } + + /* The operators below (which are not templates once this class is instanced, + * i.e.: BASE is known) can be used for implicit conversion on both sides. + * These handle operations like "vector * scalar" and "scalar * vector" by + * letting the compiler implicitly convert a scalar to a vector (assuming + * the BASE allows it). + */ + friend inline + BASE PURE operator *(const BASE& lv, const BASE& rv) { + return BASE(lv) *= rv; + } + friend inline + BASE PURE operator /(const BASE& lv, const BASE& rv) { + return BASE(lv) /= rv; + } +}; + +/* + * TVecUnaryOperators implements unary operators on a vector of type BASE. + * + * BASE only needs to implement operator[] and size(). + * By simply inheriting from TVecUnaryOperators BASE will automatically + * get all the functionality here. + * + * These operators are implemented as friend functions of TVecUnaryOperators + */ +template class BASE, typename T> +class TVecUnaryOperators { +public: + BASE& operator ++ () { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + ++rhs[i]; + } + return rhs; + } + BASE& operator -- () { + BASE& rhs = static_cast&>(*this); + for (size_t i=0 ; i::size() ; i++) { + --rhs[i]; + } + return rhs; + } + BASE operator - () const { + BASE r(BASE::NO_INIT); + BASE const& rv(static_cast const&>(*this)); + for (size_t i=0 ; i::size() ; i++) { + r[i] = -rv[i]; + } + return r; + } +}; + + +/* + * TVecComparisonOperators implements relational/comparison operators + * on a vector of type BASE. + * + * BASE only needs to implement operator[] and size(). + * By simply inheriting from TVecComparisonOperators BASE will automatically + * get all the functionality here. + */ +template class BASE, typename T> +class TVecComparisonOperators { +public: + /* + * NOTE: the functions below ARE NOT member methods. They are friend functions + * with they definition inlined with their declaration. This makes these + * template functions available to the compiler when (and only when) this class + * is instantiated, at which point they're only templated on the 2nd parameter + * (the first one, BASE being known). + */ + template + friend inline + bool PURE operator ==(const BASE& lv, const BASE& rv) { + for (size_t i = 0; i < BASE::size(); i++) + if (lv[i] != rv[i]) + return false; + return true; + } + + template + friend inline + bool PURE operator !=(const BASE& lv, const BASE& rv) { + return !operator ==(lv, rv); + } + + template + friend inline + bool PURE operator >(const BASE& lv, const BASE& rv) { + for (size_t i = 0; i < BASE::size(); i++) + if (lv[i] <= rv[i]) + return false; + return true; + } + + template + friend inline + bool PURE operator <=(const BASE& lv, const BASE& rv) { + return !(lv > rv); + } + + template + friend inline + bool PURE operator <(const BASE& lv, const BASE& rv) { + for (size_t i = 0; i < BASE::size(); i++) + if (lv[i] >= rv[i]) + return false; + return true; + } + + template + friend inline + bool PURE operator >=(const BASE& lv, const BASE& rv) { + return !(lv < rv); + } +}; + + +/* + * TVecFunctions implements functions on a vector of type BASE. + * + * BASE only needs to implement operator[] and size(). + * By simply inheriting from TVecFunctions BASE will automatically + * get all the functionality here. + */ +template class BASE, typename T> +class TVecFunctions { +public: + /* + * NOTE: the functions below ARE NOT member methods. They are friend functions + * with they definition inlined with their declaration. This makes these + * template functions available to the compiler when (and only when) this class + * is instantiated, at which point they're only templated on the 2nd parameter + * (the first one, BASE being known). + */ + template + friend inline + T PURE dot(const BASE& lv, const BASE& rv) { + T r(0); + for (size_t i = 0; i < BASE::size(); i++) + r += lv[i]*rv[i]; + return r; + } + + friend inline + T PURE length(const BASE& lv) { + return sqrt( dot(lv, lv) ); + } + + template + friend inline + T PURE distance(const BASE& lv, const BASE& rv) { + return length(rv - lv); + } + + friend inline + BASE PURE normalize(const BASE& lv) { + return lv * (1 / length(lv)); + } +}; + +#undef PURE + +// ------------------------------------------------------------------------------------- +}; // namespace android + + +#endif /* UI_TVEC_HELPERS_H */ diff --git a/third_party/android_frameworks_native/include/ui/UiConfig.h b/third_party/android_frameworks_native/include/ui/UiConfig.h new file mode 100644 index 00000000000000..fcf8ed5d6bcce1 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/UiConfig.h @@ -0,0 +1,29 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UI_CONFIG_H +#define ANDROID_UI_CONFIG_H + +#include + +namespace android { + +// Append the libui configuration details to configStr. +void appendUiConfigString(String8& configStr); + +}; // namespace android + +#endif /*ANDROID_UI_CONFIG_H*/ diff --git a/third_party/android_frameworks_native/include/ui/mat4.h b/third_party/android_frameworks_native/include/ui/mat4.h new file mode 100644 index 00000000000000..4fd1effd71a1e6 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/mat4.h @@ -0,0 +1,395 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UI_MAT4_H +#define UI_MAT4_H + +#include +#include + +#include +#include + +#define TMAT_IMPLEMENTATION +#include + +#define PURE __attribute__((pure)) + +namespace android { +// ------------------------------------------------------------------------------------- + +template +class tmat44 : public TVecUnaryOperators, + public TVecComparisonOperators, + public TVecAddOperators, + public TMatProductOperators, + public TMatSquareFunctions, + public TMatDebug +{ +public: + enum no_init { NO_INIT }; + typedef T value_type; + typedef T& reference; + typedef T const& const_reference; + typedef size_t size_type; + typedef tvec4 col_type; + typedef tvec4 row_type; + + // size of a column (i.e.: number of rows) + enum { COL_SIZE = col_type::SIZE }; + static inline size_t col_size() { return COL_SIZE; } + + // size of a row (i.e.: number of columns) + enum { ROW_SIZE = row_type::SIZE }; + static inline size_t row_size() { return ROW_SIZE; } + static inline size_t size() { return row_size(); } // for TVec*<> + +private: + + /* + * <-- N columns --> + * + * a00 a10 a20 ... aN0 ^ + * a01 a11 a21 ... aN1 | + * a02 a12 a22 ... aN2 M rows + * ... | + * a0M a1M a2M ... aNM v + * + * COL_SIZE = M + * ROW_SIZE = N + * m[0] = [a00 a01 a02 ... a01M] + */ + + col_type mValue[ROW_SIZE]; + +public: + // array access + inline col_type const& operator [] (size_t i) const { return mValue[i]; } + inline col_type& operator [] (size_t i) { return mValue[i]; } + + T const* asArray() const { return &mValue[0][0]; } + + // ----------------------------------------------------------------------- + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + /* + * constructors + */ + + // leaves object uninitialized. use with caution. + explicit tmat44(no_init) { } + + // initialize to identity + tmat44(); + + // initialize to Identity*scalar. + template + explicit tmat44(U v); + + // sets the diagonal to the passed vector + template + explicit tmat44(const tvec4& rhs); + + // construct from another matrix of the same size + template + explicit tmat44(const tmat44& rhs); + + // construct from 4 column vectors + template + tmat44(const tvec4& v0, const tvec4& v1, const tvec4& v2, const tvec4& v3); + + // construct from 16 scalars + template < + typename A, typename B, typename C, typename D, + typename E, typename F, typename G, typename H, + typename I, typename J, typename K, typename L, + typename M, typename N, typename O, typename P> + tmat44( A m00, B m01, C m02, D m03, + E m10, F m11, G m12, H m13, + I m20, J m21, K m22, L m23, + M m30, N m31, O m32, P m33); + + // construct from a C array + template + explicit tmat44(U const* rawArray); + + /* + * helpers + */ + + static tmat44 ortho(T left, T right, T bottom, T top, T near, T far); + + static tmat44 frustum(T left, T right, T bottom, T top, T near, T far); + + template + static tmat44 lookAt(const tvec3& eye, const tvec3& center, const tvec3& up); + + template + static tmat44 translate(const tvec4& t); + + template + static tmat44 scale(const tvec4& s); + + template + static tmat44 rotate(A radian, const tvec3& about); +}; + +// ---------------------------------------------------------------------------------------- +// Constructors +// ---------------------------------------------------------------------------------------- + +/* + * Since the matrix code could become pretty big quickly, we don't inline most + * operations. + */ + +template +tmat44::tmat44() { + mValue[0] = col_type(1,0,0,0); + mValue[1] = col_type(0,1,0,0); + mValue[2] = col_type(0,0,1,0); + mValue[3] = col_type(0,0,0,1); +} + +template +template +tmat44::tmat44(U v) { + mValue[0] = col_type(v,0,0,0); + mValue[1] = col_type(0,v,0,0); + mValue[2] = col_type(0,0,v,0); + mValue[3] = col_type(0,0,0,v); +} + +template +template +tmat44::tmat44(const tvec4& v) { + mValue[0] = col_type(v.x,0,0,0); + mValue[1] = col_type(0,v.y,0,0); + mValue[2] = col_type(0,0,v.z,0); + mValue[3] = col_type(0,0,0,v.w); +} + +// construct from 16 scalars +template +template < + typename A, typename B, typename C, typename D, + typename E, typename F, typename G, typename H, + typename I, typename J, typename K, typename L, + typename M, typename N, typename O, typename P> +tmat44::tmat44( A m00, B m01, C m02, D m03, + E m10, F m11, G m12, H m13, + I m20, J m21, K m22, L m23, + M m30, N m31, O m32, P m33) { + mValue[0] = col_type(m00, m01, m02, m03); + mValue[1] = col_type(m10, m11, m12, m13); + mValue[2] = col_type(m20, m21, m22, m23); + mValue[3] = col_type(m30, m31, m32, m33); +} + +template +template +tmat44::tmat44(const tmat44& rhs) { + for (size_t r=0 ; r +template +tmat44::tmat44(const tvec4& v0, const tvec4& v1, const tvec4& v2, const tvec4& v3) { + mValue[0] = v0; + mValue[1] = v1; + mValue[2] = v2; + mValue[3] = v3; +} + +template +template +tmat44::tmat44(U const* rawArray) { + for (size_t r=0 ; r +tmat44 tmat44::ortho(T left, T right, T bottom, T top, T near, T far) { + tmat44 m; + m[0][0] = 2 / (right - left); + m[1][1] = 2 / (top - bottom); + m[2][2] = -2 / (far - near); + m[3][0] = -(right + left) / (right - left); + m[3][1] = -(top + bottom) / (top - bottom); + m[3][2] = -(far + near) / (far - near); + return m; +} + +template +tmat44 tmat44::frustum(T left, T right, T bottom, T top, T near, T far) { + tmat44 m; + T A = (right + left) / (right - left); + T B = (top + bottom) / (top - bottom); + T C = (far + near) / (far - near); + T D = (2 * far * near) / (far - near); + m[0][0] = (2 * near) / (right - left); + m[1][1] = (2 * near) / (top - bottom); + m[2][0] = A; + m[2][1] = B; + m[2][2] = C; + m[2][3] =-1; + m[3][2] = D; + m[3][3] = 0; + return m; +} + +template +template +tmat44 tmat44::lookAt(const tvec3& eye, const tvec3& center, const tvec3& up) { + tvec3 L(normalize(center - eye)); + tvec3 S(normalize( cross(L, up) )); + tvec3 U(cross(S, L)); + return tmat44( + tvec4( S, 0), + tvec4( U, 0), + tvec4(-L, 0), + tvec4(-eye, 1)); +} + +template +template +tmat44 tmat44::translate(const tvec4& t) { + tmat44 r; + r[3] = t; + return r; +} + +template +template +tmat44 tmat44::scale(const tvec4& s) { + tmat44 r; + r[0][0] = s[0]; + r[1][1] = s[1]; + r[2][2] = s[2]; + r[3][3] = s[3]; + return r; +} + +template +template +tmat44 tmat44::rotate(A radian, const tvec3& about) { + tmat44 rotation; + T* r = const_cast(rotation.asArray()); + T c = cos(radian); + T s = sin(radian); + if (about.x==1 && about.y==0 && about.z==0) { + r[5] = c; r[10]= c; + r[6] = s; r[9] = -s; + } else if (about.x==0 && about.y==1 && about.z==0) { + r[0] = c; r[10]= c; + r[8] = s; r[2] = -s; + } else if (about.x==0 && about.y==0 && about.z==1) { + r[0] = c; r[5] = c; + r[1] = s; r[4] = -s; + } else { + tvec3 nabout = normalize(about); + B x = nabout.x; + B y = nabout.y; + B z = nabout.z; + T nc = 1 - c; + T xy = x * y; + T yz = y * z; + T zx = z * x; + T xs = x * s; + T ys = y * s; + T zs = z * s; + r[ 0] = x*x*nc + c; r[ 4] = xy*nc - zs; r[ 8] = zx*nc + ys; + r[ 1] = xy*nc + zs; r[ 5] = y*y*nc + c; r[ 9] = yz*nc - xs; + r[ 2] = zx*nc - ys; r[ 6] = yz*nc + xs; r[10] = z*z*nc + c; + } + return rotation; +} + +// ---------------------------------------------------------------------------------------- +// Arithmetic operators outside of class +// ---------------------------------------------------------------------------------------- + +/* We use non-friend functions here to prevent the compiler from using + * implicit conversions, for instance of a scalar to a vector. The result would + * not be what the caller expects. + * + * Also note that the order of the arguments in the inner loop is important since + * it determines the output type (only relevant when T != U). + */ + +// matrix * vector, result is a vector of the same type than the input vector +template +typename tmat44::col_type PURE operator *(const tmat44& lv, const tvec4& rv) { + typename tmat44::col_type result; + for (size_t r=0 ; r::row_size() ; r++) + result += rv[r]*lv[r]; + return result; +} + +// vector * matrix, result is a vector of the same type than the input vector +template +typename tmat44::row_type PURE operator *(const tvec4& rv, const tmat44& lv) { + typename tmat44::row_type result(tmat44::row_type::NO_INIT); + for (size_t r=0 ; r::row_size() ; r++) + result[r] = dot(rv, lv[r]); + return result; +} + +// matrix * scalar, result is a matrix of the same type than the input matrix +template +tmat44 PURE operator *(const tmat44& lv, U rv) { + tmat44 result(tmat44::NO_INIT); + for (size_t r=0 ; r::row_size() ; r++) + result[r] = lv[r]*rv; + return result; +} + +// scalar * matrix, result is a matrix of the same type than the input matrix +template +tmat44 PURE operator *(U rv, const tmat44& lv) { + tmat44 result(tmat44::NO_INIT); + for (size_t r=0 ; r::row_size() ; r++) + result[r] = lv[r]*rv; + return result; +} + +// ---------------------------------------------------------------------------------------- + +/* FIXME: this should go into TMatSquareFunctions<> but for some reason + * BASE::col_type is not accessible from there (???) + */ +template +typename tmat44::col_type PURE diag(const tmat44& m) { + return matrix::diag(m); +} + +// ---------------------------------------------------------------------------------------- + +typedef tmat44 mat4; + +// ---------------------------------------------------------------------------------------- +}; // namespace android + +#undef PURE + +#endif /* UI_MAT4_H */ diff --git a/third_party/android_frameworks_native/include/ui/vec2.h b/third_party/android_frameworks_native/include/ui/vec2.h new file mode 100644 index 00000000000000..c31d0e43e38934 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/vec2.h @@ -0,0 +1,91 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UI_VEC2_H +#define UI_VEC2_H + +#include +#include + +#define TVEC_IMPLEMENTATION +#include + +namespace android { +// ------------------------------------------------------------------------------------- + +template +class tvec2 : public TVecProductOperators, + public TVecAddOperators, + public TVecUnaryOperators, + public TVecComparisonOperators, + public TVecFunctions +{ +public: + enum no_init { NO_INIT }; + typedef T value_type; + typedef T& reference; + typedef T const& const_reference; + typedef size_t size_type; + + union { + struct { T x, y; }; + struct { T s, t; }; + struct { T r, g; }; + }; + + enum { SIZE = 2 }; + inline static size_type size() { return SIZE; } + + // array access + inline T const& operator [] (size_t i) const { return (&x)[i]; } + inline T& operator [] (size_t i) { return (&x)[i]; } + + // ----------------------------------------------------------------------- + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + // constructors + + // leaves object uninitialized. use with caution. + explicit tvec2(no_init) { } + + // default constructor + tvec2() : x(0), y(0) { } + + // handles implicit conversion to a tvec4. must not be explicit. + template + tvec2(A v) : x(v), y(v) { } + + template + tvec2(A x, B y) : x(x), y(y) { } + + template + explicit tvec2(const tvec2& v) : x(v.x), y(v.y) { } + + template + tvec2(const Impersonator< tvec2 >& v) + : x(((const tvec2&)v).x), + y(((const tvec2&)v).y) { } +}; + +// ---------------------------------------------------------------------------------------- + +typedef tvec2 vec2; + +// ---------------------------------------------------------------------------------------- +}; // namespace android + +#endif /* UI_VEC4_H */ diff --git a/third_party/android_frameworks_native/include/ui/vec3.h b/third_party/android_frameworks_native/include/ui/vec3.h new file mode 100644 index 00000000000000..dde59a96fbe631 --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/vec3.h @@ -0,0 +1,113 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UI_VEC3_H +#define UI_VEC3_H + +#include +#include + +#include + +namespace android { +// ------------------------------------------------------------------------------------- + +template +class tvec3 : public TVecProductOperators, + public TVecAddOperators, + public TVecUnaryOperators, + public TVecComparisonOperators, + public TVecFunctions +{ +public: + enum no_init { NO_INIT }; + typedef T value_type; + typedef T& reference; + typedef T const& const_reference; + typedef size_t size_type; + + union { + struct { T x, y, z; }; + struct { T s, t, p; }; + struct { T r, g, b; }; + Impersonator< tvec2 > xy; + Impersonator< tvec2 > st; + Impersonator< tvec2 > rg; + }; + + enum { SIZE = 3 }; + inline static size_type size() { return SIZE; } + + // array access + inline T const& operator [] (size_t i) const { return (&x)[i]; } + inline T& operator [] (size_t i) { return (&x)[i]; } + + // ----------------------------------------------------------------------- + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + // constructors + // leaves object uninitialized. use with caution. + explicit tvec3(no_init) { } + + // default constructor + tvec3() : x(0), y(0), z(0) { } + + // handles implicit conversion to a tvec4. must not be explicit. + template + tvec3(A v) : x(v), y(v), z(v) { } + + template + tvec3(A x, B y, C z) : x(x), y(y), z(z) { } + + template + tvec3(const tvec2& v, B z) : x(v.x), y(v.y), z(z) { } + + template + explicit tvec3(const tvec3& v) : x(v.x), y(v.y), z(v.z) { } + + template + tvec3(const Impersonator< tvec3 >& v) + : x(((const tvec3&)v).x), + y(((const tvec3&)v).y), + z(((const tvec3&)v).z) { } + + template + tvec3(const Impersonator< tvec2 >& v, B z) + : x(((const tvec2&)v).x), + y(((const tvec2&)v).y), + z(z) { } + + // cross product works only on vectors of size 3 + template + friend inline + tvec3 __attribute__((pure)) cross(const tvec3& u, const tvec3& v) { + return tvec3( + u.y*v.z - u.z*v.y, + u.z*v.x - u.x*v.z, + u.x*v.y - u.y*v.x); + } +}; + + +// ---------------------------------------------------------------------------------------- + +typedef tvec3 vec3; + +// ---------------------------------------------------------------------------------------- +}; // namespace android + +#endif /* UI_VEC4_H */ diff --git a/third_party/android_frameworks_native/include/ui/vec4.h b/third_party/android_frameworks_native/include/ui/vec4.h new file mode 100644 index 00000000000000..e03d331fb353ff --- /dev/null +++ b/third_party/android_frameworks_native/include/ui/vec4.h @@ -0,0 +1,118 @@ +/* + * Copyright 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UI_VEC4_H +#define UI_VEC4_H + +#include +#include + +#include + +namespace android { +// ------------------------------------------------------------------------------------- + +template +class tvec4 : public TVecProductOperators, + public TVecAddOperators, + public TVecUnaryOperators, + public TVecComparisonOperators, + public TVecFunctions +{ +public: + enum no_init { NO_INIT }; + typedef T value_type; + typedef T& reference; + typedef T const& const_reference; + typedef size_t size_type; + + union { + struct { T x, y, z, w; }; + struct { T s, t, p, q; }; + struct { T r, g, b, a; }; + Impersonator< tvec2 > xy; + Impersonator< tvec2 > st; + Impersonator< tvec2 > rg; + Impersonator< tvec3 > xyz; + Impersonator< tvec3 > stp; + Impersonator< tvec3 > rgb; + }; + + enum { SIZE = 4 }; + inline static size_type size() { return SIZE; } + + // array access + inline T const& operator [] (size_t i) const { return (&x)[i]; } + inline T& operator [] (size_t i) { return (&x)[i]; } + + // ----------------------------------------------------------------------- + // we don't provide copy-ctor and operator= on purpose + // because we want the compiler generated versions + + // constructors + + // leaves object uninitialized. use with caution. + explicit tvec4(no_init) { } + + // default constructor + tvec4() : x(0), y(0), z(0), w(0) { } + + // handles implicit conversion to a tvec4. must not be explicit. + template + tvec4(A v) : x(v), y(v), z(v), w(v) { } + + template + tvec4(A x, B y, C z, D w) : x(x), y(y), z(z), w(w) { } + + template + tvec4(const tvec2& v, B z, C w) : x(v.x), y(v.y), z(z), w(w) { } + + template + tvec4(const tvec3& v, B w) : x(v.x), y(v.y), z(v.z), w(w) { } + + template + explicit tvec4(const tvec4& v) : x(v.x), y(v.y), z(v.z), w(v.w) { } + + template + tvec4(const Impersonator< tvec4 >& v) + : x(((const tvec4&)v).x), + y(((const tvec4&)v).y), + z(((const tvec4&)v).z), + w(((const tvec4&)v).w) { } + + template + tvec4(const Impersonator< tvec3 >& v, B w) + : x(((const tvec3&)v).x), + y(((const tvec3&)v).y), + z(((const tvec3&)v).z), + w(w) { } + + template + tvec4(const Impersonator< tvec2 >& v, B z, C w) + : x(((const tvec2&)v).x), + y(((const tvec2&)v).y), + z(z), + w(w) { } +}; + +// ---------------------------------------------------------------------------------------- + +typedef tvec4 vec4; + +// ---------------------------------------------------------------------------------------- +}; // namespace android + +#endif /* UI_VEC4_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/activity_recognition.h b/third_party/android_hardware_libhardware/include/hardware/activity_recognition.h new file mode 100644 index 00000000000000..8f9945982ded2a --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/activity_recognition.h @@ -0,0 +1,223 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * Activity Recognition HAL. The goal is to provide low power, low latency, always-on activity + * recognition implemented in hardware (i.e. these activity recognition algorithms/classifers + * should NOT be run on the AP). By low power we mean that this may be activated 24/7 without + * impacting the battery drain speed (goal in order of 1mW including the power for sensors). + * This HAL does not specify the input sources that are used towards detecting these activities. + * It has one monitor interface which can be used to batch activities for always-on + * activity_recognition and if the latency is zero, the same interface can be used for low latency + * detection. + */ + +#ifndef ANDROID_ACTIVITY_RECOGNITION_INTERFACE_H +#define ANDROID_ACTIVITY_RECOGNITION_INTERFACE_H + +#include + +__BEGIN_DECLS + +#define ACTIVITY_RECOGNITION_HEADER_VERSION 1 +#define ACTIVITY_RECOGNITION_API_VERSION_0_1 HARDWARE_DEVICE_API_VERSION_2(0, 1, ACTIVITY_RECOGNITION_HEADER_VERSION) + +#define ACTIVITY_RECOGNITION_HARDWARE_MODULE_ID "activity_recognition" +#define ACTIVITY_RECOGNITION_HARDWARE_INTERFACE "activity_recognition_hw_if" + +/* + * Define types for various activities. Multiple activities may be active at the same time and + * sometimes none of these activities may be active. + * + * Each activity has a corresponding type. Only activities that are defined here should use + * android.activity_recognition.* prefix. OEM defined activities should not use this prefix. + * Activity type of OEM-defined activities should start with the reverse domain name of the entity + * defining the activity. + * + * When android introduces a new activity type that can potentially replace an OEM-defined activity + * type, the OEM must use the official activity type on versions of the HAL that support this new + * official activity type. + * + * Example (made up): Suppose Google's Glass team wants to detect nodding activity. + * - Such an activity is not officially supported in android L + * - Glass devices launching on L can implement a custom activity with + * type = "com.google.glass.nodding" + * - In M android release, if android decides to define ACITIVITY_TYPE_NODDING, those types + * should replace the Glass-team-specific types in all future launches. + * - When launching glass on the M release, Google should now use the official activity type + * - This way, other applications can use this activity. + */ + +#define ACTIVITY_TYPE_IN_VEHICLE "android.activity_recognition.in_vehicle" + +#define ACTIVITY_TYPE_ON_BICYCLE "android.activity_recognition.on_bicycle" + +#define ACTIVITY_TYPE_WALKING "android.activity_recognition.walking" + +#define ACTIVITY_TYPE_RUNNING "android.activity_recognition.running" + +#define ACTIVITY_TYPE_STILL "android.activity_recognition.still" + +#define ACTIVITY_TYPE_TILTING "android.activity_recognition.tilting" + +/* Values for activity_event.event_types. */ +enum { + /* + * A flush_complete event which indicates that a flush() has been successfully completed. This + * does not correspond to any activity/event. An event of this type should be added to the end + * of a batch FIFO and it indicates that all the events in the batch FIFO have been successfully + * reported to the framework. An event of this type should be generated only if flush() has been + * explicitly called and if the FIFO is empty at the time flush() is called it should trivially + * return a flush_complete_event to indicate that the FIFO is empty. + * + * A flush complete event should have the following parameters set. + * activity_event_t.event_type = ACTIVITY_EVENT_FLUSH_COMPLETE + * activity_event_t.activity = 0 + * activity_event_t.timestamp = 0 + * activity_event_t.reserved = 0 + * See (*flush)() for more details. + */ + ACTIVITY_EVENT_FLUSH_COMPLETE = 0, + + /* Signifies entering an activity. */ + ACTIVITY_EVENT_ENTER = 1, + + /* Signifies exiting an activity. */ + ACTIVITY_EVENT_EXIT = 2 +}; + +/* + * Each event is a separate activity with event_type indicating whether this activity has started + * or ended. Eg event: (event_type="enter", activity="ON_FOOT", timestamp) + */ +typedef struct activity_event { + /* One of the ACTIVITY_EVENT_* constants defined above. */ + uint32_t event_type; + + /* + * Index of the activity in the list returned by get_supported_activities_list. If this event + * is a flush complete event, this should be set to zero. + */ + uint32_t activity; + + /* Time at which the transition/event has occurred in nanoseconds using elapsedRealTimeNano. */ + int64_t timestamp; + + /* Set to zero. */ + int32_t reserved[4]; +} activity_event_t; + +typedef struct activity_recognition_module { + /** + * Common methods of the activity recognition module. This *must* be the first member of + * activity_recognition_module as users of this structure will cast a hw_module_t to + * activity_recognition_module pointer in contexts where it's known the hw_module_t + * references an activity_recognition_module. + */ + hw_module_t common; + + /* + * List of all activities supported by this module including OEM defined activities. Each + * activity is represented using a string defined above. Each string should be null terminated. + * The index of the activity in this array is used as a "handle" for enabling/disabling and + * event delivery. + * Return value is the size of this list. + */ + int (*get_supported_activities_list)(struct activity_recognition_module* module, + char const* const* *activity_list); +} activity_recognition_module_t; + +struct activity_recognition_device; + +typedef struct activity_recognition_callback_procs { + // Callback for activity_data. This is guaranteed to not invoke any HAL methods. + // Memory allocated for the events can be reused after this method returns. + // events - Array of activity_event_t s that are reported. + // count - size of the array. + void (*activity_callback)(const struct activity_recognition_callback_procs* procs, + const activity_event_t* events, int count); +} activity_recognition_callback_procs_t; + +typedef struct activity_recognition_device { + /** + * Common methods of the activity recognition device. This *must* be the first member of + * activity_recognition_device as users of this structure will cast a hw_device_t to + * activity_recognition_device pointer in contexts where it's known the hw_device_t + * references an activity_recognition_device. + */ + hw_device_t common; + + /* + * Sets the callback to invoke when there are events to report. This call overwrites the + * previously registered callback (if any). + */ + void (*register_activity_callback)(const struct activity_recognition_device* dev, + const activity_recognition_callback_procs_t* callback); + + /* + * Activates monitoring of activity transitions. Activities need not be reported as soon as they + * are detected. The detected activities are stored in a FIFO and reported in batches when the + * "max_batch_report_latency" expires or when the batch FIFO is full. The implementation should + * allow the AP to go into suspend mode while the activities are detected and stored in the + * batch FIFO. Whenever events need to be reported (like when the FIFO is full or when the + * max_batch_report_latency has expired for an activity, event pair), it should wake_up the AP + * so that no events are lost. Activities are stored as transitions and they are allowed to + * overlap with each other. Each (activity, event_type) pair can be activated or deactivated + * independently of the other. The HAL implementation needs to keep track of which pairs are + * currently active and needs to detect only those pairs. + * + * activity_handle - Index of the specific activity that needs to be detected in the list + * returned by get_supported_activities_list. + * event_type - Specific transition of the activity that needs to be detected. + * max_batch_report_latency_ns - a transition can be delayed by at most + * “max_batch_report_latency” nanoseconds. + * Return 0 on success, negative errno code otherwise. + */ + int (*enable_activity_event)(const struct activity_recognition_device* dev, + uint32_t activity_handle, uint32_t event_type, int64_t max_batch_report_latency_ns); + + /* + * Disables detection of a specific (activity, event_type) pair. + */ + int (*disable_activity_event)(const struct activity_recognition_device* dev, + uint32_t activity_handle, uint32_t event_type); + + /* + * Flush all the batch FIFOs. Report all the activities that were stored in the FIFO so far as + * if max_batch_report_latency had expired. This shouldn't change the latency in any way. Add + * a flush_complete_event to indicate the end of the FIFO after all events are delivered. + * See ACTIVITY_EVENT_FLUSH_COMPLETE for more details. + * Return 0 on success, negative errno code otherwise. + */ + int (*flush)(const struct activity_recognition_device* dev); + + // Must be set to NULL. + void (*reserved_procs[16 - 4])(void); +} activity_recognition_device_t; + +static inline int activity_recognition_open(const hw_module_t* module, + activity_recognition_device_t** device) { + return module->methods->open(module, + ACTIVITY_RECOGNITION_HARDWARE_INTERFACE, (hw_device_t**)device); +} + +static inline int activity_recognition_close(activity_recognition_device_t* device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_ACTIVITY_RECOGNITION_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/audio.h b/third_party/android_hardware_libhardware/include/hardware/audio.h new file mode 100644 index 00000000000000..22e74197694920 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/audio.h @@ -0,0 +1,700 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_AUDIO_HAL_INTERFACE_H +#define ANDROID_AUDIO_HAL_INTERFACE_H + +#include +#include +#include +#include + +#include + +#include +#include +#include +#ifdef AUDIO_LISTEN_ENABLED +#include +#endif + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define AUDIO_HARDWARE_MODULE_ID "audio" + +/** + * Name of the audio devices to open + */ +#define AUDIO_HARDWARE_INTERFACE "audio_hw_if" + + +/* Use version 0.1 to be compatible with first generation of audio hw module with version_major + * hardcoded to 1. No audio module API change. + */ +#define AUDIO_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) +#define AUDIO_MODULE_API_VERSION_CURRENT AUDIO_MODULE_API_VERSION_0_1 + +/* First generation of audio devices had version hardcoded to 0. all devices with versions < 1.0 + * will be considered of first generation API. + */ +#define AUDIO_DEVICE_API_VERSION_0_0 HARDWARE_DEVICE_API_VERSION(0, 0) +#define AUDIO_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define AUDIO_DEVICE_API_VERSION_2_0 HARDWARE_DEVICE_API_VERSION(2, 0) +#define AUDIO_DEVICE_API_VERSION_3_0 HARDWARE_DEVICE_API_VERSION(3, 0) +#define AUDIO_DEVICE_API_VERSION_CURRENT AUDIO_DEVICE_API_VERSION_3_0 +/* Minimal audio HAL version supported by the audio framework */ +#define AUDIO_DEVICE_API_VERSION_MIN AUDIO_DEVICE_API_VERSION_2_0 + +/** + * List of known audio HAL modules. This is the base name of the audio HAL + * library composed of the "audio." prefix, one of the base names below and + * a suffix specific to the device. + * e.g: audio.primary.goldfish.so or audio.a2dp.default.so + */ + +#define AUDIO_HARDWARE_MODULE_ID_PRIMARY "primary" +#define AUDIO_HARDWARE_MODULE_ID_A2DP "a2dp" +#define AUDIO_HARDWARE_MODULE_ID_USB "usb" +#define AUDIO_HARDWARE_MODULE_ID_REMOTE_SUBMIX "r_submix" +#define AUDIO_HARDWARE_MODULE_ID_CODEC_OFFLOAD "codec_offload" + +/**************************************/ + +/** + * standard audio parameters that the HAL may need to handle + */ + +/** + * audio device parameters + */ + +/* BT SCO Noise Reduction + Echo Cancellation parameters */ +#define AUDIO_PARAMETER_KEY_BT_NREC "bt_headset_nrec" +#define AUDIO_PARAMETER_VALUE_ON "on" +#define AUDIO_PARAMETER_VALUE_OFF "off" + +/* TTY mode selection */ +#define AUDIO_PARAMETER_KEY_TTY_MODE "tty_mode" +#define AUDIO_PARAMETER_VALUE_TTY_OFF "tty_off" +#define AUDIO_PARAMETER_VALUE_TTY_VCO "tty_vco" +#define AUDIO_PARAMETER_VALUE_TTY_HCO "tty_hco" +#define AUDIO_PARAMETER_VALUE_TTY_FULL "tty_full" + +/* Hearing Aid Compatibility - Telecoil (HAC-T) mode on/off + Strings must be in sync with CallFeaturesSetting.java */ +#define AUDIO_PARAMETER_KEY_HAC "HACSetting" +#define AUDIO_PARAMETER_VALUE_HAC_ON "ON" +#define AUDIO_PARAMETER_VALUE_HAC_OFF "OFF" + +/* A2DP sink address set by framework */ +#define AUDIO_PARAMETER_A2DP_SINK_ADDRESS "a2dp_sink_address" + +/* A2DP source address set by framework */ +#define AUDIO_PARAMETER_A2DP_SOURCE_ADDRESS "a2dp_source_address" + +/* Screen state */ +#define AUDIO_PARAMETER_KEY_SCREEN_STATE "screen_state" + +/* Bluetooth SCO wideband */ +#define AUDIO_PARAMETER_KEY_BT_SCO_WB "bt_wbs" + +/* Get a new HW synchronization source identifier. + * Return a valid source (positive integer) or AUDIO_HW_SYNC_INVALID if an error occurs + * or no HW sync is available. */ +#define AUDIO_PARAMETER_HW_AV_SYNC "hw_av_sync" + +/* Device state*/ +#define AUDIO_PARAMETER_KEY_DEV_SHUTDOWN "dev_shutdown" + +/** + * audio stream parameters + */ + +#define AUDIO_PARAMETER_STREAM_ROUTING "routing" /* audio_devices_t */ +#define AUDIO_PARAMETER_STREAM_FORMAT "format" /* audio_format_t */ +#define AUDIO_PARAMETER_STREAM_CHANNELS "channels" /* audio_channel_mask_t */ +#define AUDIO_PARAMETER_STREAM_FRAME_COUNT "frame_count" /* size_t */ +#define AUDIO_PARAMETER_STREAM_INPUT_SOURCE "input_source" /* audio_source_t */ +#define AUDIO_PARAMETER_STREAM_SAMPLING_RATE "sampling_rate" /* uint32_t */ + +#define AUDIO_PARAMETER_DEVICE_CONNECT "connect" /* audio_devices_t */ +#define AUDIO_PARAMETER_DEVICE_DISCONNECT "disconnect" /* audio_devices_t */ + +/* Query supported formats. The response is a '|' separated list of strings from + * audio_format_t enum e.g: "sup_formats=AUDIO_FORMAT_PCM_16_BIT" */ +#define AUDIO_PARAMETER_STREAM_SUP_FORMATS "sup_formats" +/* Query supported channel masks. The response is a '|' separated list of strings from + * audio_channel_mask_t enum e.g: "sup_channels=AUDIO_CHANNEL_OUT_STEREO|AUDIO_CHANNEL_OUT_MONO" */ +#define AUDIO_PARAMETER_STREAM_SUP_CHANNELS "sup_channels" +/* Query supported sampling rates. The response is a '|' separated list of integer values e.g: + * "sup_sampling_rates=44100|48000" */ +#define AUDIO_PARAMETER_STREAM_SUP_SAMPLING_RATES "sup_sampling_rates" + +/* Set the HW synchronization source for an output stream. */ +#define AUDIO_PARAMETER_STREAM_HW_AV_SYNC "hw_av_sync" + +/** + * audio codec parameters + */ + +#define AUDIO_OFFLOAD_CODEC_PARAMS "music_offload_codec_param" +#define AUDIO_OFFLOAD_CODEC_BIT_PER_SAMPLE "music_offload_bit_per_sample" +#define AUDIO_OFFLOAD_CODEC_BIT_RATE "music_offload_bit_rate" +#define AUDIO_OFFLOAD_CODEC_AVG_BIT_RATE "music_offload_avg_bit_rate" +#define AUDIO_OFFLOAD_CODEC_ID "music_offload_codec_id" +#define AUDIO_OFFLOAD_CODEC_BLOCK_ALIGN "music_offload_block_align" +#define AUDIO_OFFLOAD_CODEC_SAMPLE_RATE "music_offload_sample_rate" +#define AUDIO_OFFLOAD_CODEC_ENCODE_OPTION "music_offload_encode_option" +#define AUDIO_OFFLOAD_CODEC_NUM_CHANNEL "music_offload_num_channels" +#define AUDIO_OFFLOAD_CODEC_DOWN_SAMPLING "music_offload_down_sampling" +#define AUDIO_OFFLOAD_CODEC_DELAY_SAMPLES "delay_samples" +#define AUDIO_OFFLOAD_CODEC_PADDING_SAMPLES "padding_samples" + +/**************************************/ + +/* common audio stream parameters and operations */ +struct audio_stream { + + /** + * Return the sampling rate in Hz - eg. 44100. + */ + uint32_t (*get_sample_rate)(const struct audio_stream *stream); + + /* currently unused - use set_parameters with key + * AUDIO_PARAMETER_STREAM_SAMPLING_RATE + */ + int (*set_sample_rate)(struct audio_stream *stream, uint32_t rate); + + /** + * Return size of input/output buffer in bytes for this stream - eg. 4800. + * It should be a multiple of the frame size. See also get_input_buffer_size. + */ + size_t (*get_buffer_size)(const struct audio_stream *stream); + + /** + * Return the channel mask - + * e.g. AUDIO_CHANNEL_OUT_STEREO or AUDIO_CHANNEL_IN_STEREO + */ + audio_channel_mask_t (*get_channels)(const struct audio_stream *stream); + + /** + * Return the audio format - e.g. AUDIO_FORMAT_PCM_16_BIT + */ + audio_format_t (*get_format)(const struct audio_stream *stream); + + /* currently unused - use set_parameters with key + * AUDIO_PARAMETER_STREAM_FORMAT + */ + int (*set_format)(struct audio_stream *stream, audio_format_t format); + + /** + * Put the audio hardware input/output into standby mode. + * Driver should exit from standby mode at the next I/O operation. + * Returns 0 on success and <0 on failure. + */ + int (*standby)(struct audio_stream *stream); + + /** dump the state of the audio input/output device */ + int (*dump)(const struct audio_stream *stream, int fd); + + /** Return the set of device(s) which this stream is connected to */ + audio_devices_t (*get_device)(const struct audio_stream *stream); + + /** + * Currently unused - set_device() corresponds to set_parameters() with key + * AUDIO_PARAMETER_STREAM_ROUTING for both input and output. + * AUDIO_PARAMETER_STREAM_INPUT_SOURCE is an additional information used by + * input streams only. + */ + int (*set_device)(struct audio_stream *stream, audio_devices_t device); + + /** + * set/get audio stream parameters. The function accepts a list of + * parameter key value pairs in the form: key1=value1;key2=value2;... + * + * Some keys are reserved for standard parameters (See AudioParameter class) + * + * If the implementation does not accept a parameter change while + * the output is active but the parameter is acceptable otherwise, it must + * return -ENOSYS. + * + * The audio flinger will put the stream in standby and then change the + * parameter value. + */ + int (*set_parameters)(struct audio_stream *stream, const char *kv_pairs); + + /* + * Returns a pointer to a heap allocated string. The caller is responsible + * for freeing the memory for it using free(). + */ + char * (*get_parameters)(const struct audio_stream *stream, + const char *keys); + int (*add_audio_effect)(const struct audio_stream *stream, + effect_handle_t effect); + int (*remove_audio_effect)(const struct audio_stream *stream, + effect_handle_t effect); +}; +typedef struct audio_stream audio_stream_t; + +/* type of asynchronous write callback events. Mutually exclusive */ +typedef enum { + STREAM_CBK_EVENT_WRITE_READY, /* non blocking write completed */ + STREAM_CBK_EVENT_DRAIN_READY /* drain completed */ +} stream_callback_event_t; + +typedef int (*stream_callback_t)(stream_callback_event_t event, void *param, void *cookie); + +/* type of drain requested to audio_stream_out->drain(). Mutually exclusive */ +typedef enum { + AUDIO_DRAIN_ALL, /* drain() returns when all data has been played */ + AUDIO_DRAIN_EARLY_NOTIFY /* drain() returns a short time before all data + from the current track has been played to + give time for gapless track switch */ +} audio_drain_type_t; + +/** + * audio_stream_out is the abstraction interface for the audio output hardware. + * + * It provides information about various properties of the audio output + * hardware driver. + */ + +struct audio_stream_out { + /** + * Common methods of the audio stream out. This *must* be the first member of audio_stream_out + * as users of this structure will cast a audio_stream to audio_stream_out pointer in contexts + * where it's known the audio_stream references an audio_stream_out. + */ + struct audio_stream common; + + /** + * Return the audio hardware driver estimated latency in milliseconds. + */ + uint32_t (*get_latency)(const struct audio_stream_out *stream); + + /** + * Use this method in situations where audio mixing is done in the + * hardware. This method serves as a direct interface with hardware, + * allowing you to directly set the volume as apposed to via the framework. + * This method might produce multiple PCM outputs or hardware accelerated + * codecs, such as MP3 or AAC. + */ + int (*set_volume)(struct audio_stream_out *stream, float left, float right); + + /** + * Write audio buffer to driver. Returns number of bytes written, or a + * negative status_t. If at least one frame was written successfully prior to the error, + * it is suggested that the driver return that successful (short) byte count + * and then return an error in the subsequent call. + * + * If set_callback() has previously been called to enable non-blocking mode + * the write() is not allowed to block. It must write only the number of + * bytes that currently fit in the driver/hardware buffer and then return + * this byte count. If this is less than the requested write size the + * callback function must be called when more space is available in the + * driver/hardware buffer. + */ + ssize_t (*write)(struct audio_stream_out *stream, const void* buffer, + size_t bytes); + + /* return the number of audio frames written by the audio dsp to DAC since + * the output has exited standby + */ + int (*get_render_position)(const struct audio_stream_out *stream, + uint32_t *dsp_frames); + + /** + * get the local time at which the next write to the audio driver will be presented. + * The units are microseconds, where the epoch is decided by the local audio HAL. + */ + int (*get_next_write_timestamp)(const struct audio_stream_out *stream, + int64_t *timestamp); + + /** + * set the callback function for notifying completion of non-blocking + * write and drain. + * Calling this function implies that all future write() and drain() + * must be non-blocking and use the callback to signal completion. + */ + int (*set_callback)(struct audio_stream_out *stream, + stream_callback_t callback, void *cookie); + + /** + * Notifies to the audio driver to stop playback however the queued buffers are + * retained by the hardware. Useful for implementing pause/resume. Empty implementation + * if not supported however should be implemented for hardware with non-trivial + * latency. In the pause state audio hardware could still be using power. User may + * consider calling suspend after a timeout. + * + * Implementation of this function is mandatory for offloaded playback. + */ + int (*pause)(struct audio_stream_out* stream); + + /** + * Notifies to the audio driver to resume playback following a pause. + * Returns error if called without matching pause. + * + * Implementation of this function is mandatory for offloaded playback. + */ + int (*resume)(struct audio_stream_out* stream); + + /** + * Requests notification when data buffered by the driver/hardware has + * been played. If set_callback() has previously been called to enable + * non-blocking mode, the drain() must not block, instead it should return + * quickly and completion of the drain is notified through the callback. + * If set_callback() has not been called, the drain() must block until + * completion. + * If type==AUDIO_DRAIN_ALL, the drain completes when all previously written + * data has been played. + * If type==AUDIO_DRAIN_EARLY_NOTIFY, the drain completes shortly before all + * data for the current track has played to allow time for the framework + * to perform a gapless track switch. + * + * Drain must return immediately on stop() and flush() call + * + * Implementation of this function is mandatory for offloaded playback. + */ + int (*drain)(struct audio_stream_out* stream, audio_drain_type_t type ); + + /** + * Notifies to the audio driver to flush the queued data. Stream must already + * be paused before calling flush(). + * + * Implementation of this function is mandatory for offloaded playback. + */ + int (*flush)(struct audio_stream_out* stream); + + /** + * Return a recent count of the number of audio frames presented to an external observer. + * This excludes frames which have been written but are still in the pipeline. + * The count is not reset to zero when output enters standby. + * Also returns the value of CLOCK_MONOTONIC as of this presentation count. + * The returned count is expected to be 'recent', + * but does not need to be the most recent possible value. + * However, the associated time should correspond to whatever count is returned. + * Example: assume that N+M frames have been presented, where M is a 'small' number. + * Then it is permissible to return N instead of N+M, + * and the timestamp should correspond to N rather than N+M. + * The terms 'recent' and 'small' are not defined. + * They reflect the quality of the implementation. + * + * 3.0 and higher only. + */ + int (*get_presentation_position)(const struct audio_stream_out *stream, + uint64_t *frames, struct timespec *timestamp); + +}; +typedef struct audio_stream_out audio_stream_out_t; + +struct audio_stream_in { + /** + * Common methods of the audio stream in. This *must* be the first member of audio_stream_in + * as users of this structure will cast a audio_stream to audio_stream_in pointer in contexts + * where it's known the audio_stream references an audio_stream_in. + */ + struct audio_stream common; + + /** set the input gain for the audio driver. This method is for + * for future use */ + int (*set_gain)(struct audio_stream_in *stream, float gain); + + /** Read audio buffer in from audio driver. Returns number of bytes read, or a + * negative status_t. If at least one frame was read prior to the error, + * read should return that byte count and then return an error in the subsequent call. + */ + ssize_t (*read)(struct audio_stream_in *stream, void* buffer, + size_t bytes); + + /** + * Return the amount of input frames lost in the audio driver since the + * last call of this function. + * Audio driver is expected to reset the value to 0 and restart counting + * upon returning the current value by this function call. + * Such loss typically occurs when the user space process is blocked + * longer than the capacity of audio driver buffers. + * + * Unit: the number of input audio frames + */ + uint32_t (*get_input_frames_lost)(struct audio_stream_in *stream); +}; +typedef struct audio_stream_in audio_stream_in_t; + +/** + * return the frame size (number of bytes per sample). + * + * Deprecated: use audio_stream_out_frame_size() or audio_stream_in_frame_size() instead. + */ +__attribute__((__deprecated__)) +static inline size_t audio_stream_frame_size(const struct audio_stream *s) +{ + size_t chan_samp_sz; + audio_format_t format = s->get_format(s); + + if (audio_is_linear_pcm(format)) { + chan_samp_sz = audio_bytes_per_sample(format); + return popcount(s->get_channels(s)) * chan_samp_sz; + } + + return sizeof(int8_t); +} + +/** + * return the frame size (number of bytes per sample) of an output stream. + */ +static inline size_t audio_stream_out_frame_size(const struct audio_stream_out *s) +{ + size_t chan_samp_sz; + audio_format_t format = s->common.get_format(&s->common); + + if (audio_is_linear_pcm(format)) { + chan_samp_sz = audio_bytes_per_sample(format); + return audio_channel_count_from_out_mask(s->common.get_channels(&s->common)) * chan_samp_sz; + } + + return sizeof(int8_t); +} + +/** + * return the frame size (number of bytes per sample) of an input stream. + */ +static inline size_t audio_stream_in_frame_size(const struct audio_stream_in *s) +{ + size_t chan_samp_sz; + audio_format_t format = s->common.get_format(&s->common); + + if (audio_is_linear_pcm(format)) { + chan_samp_sz = audio_bytes_per_sample(format); + return audio_channel_count_from_in_mask(s->common.get_channels(&s->common)) * chan_samp_sz; + } + + return sizeof(int8_t); +} + +/**********************************************************************/ + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +struct audio_module { + struct hw_module_t common; +}; + +struct audio_hw_device { + /** + * Common methods of the audio device. This *must* be the first member of audio_hw_device + * as users of this structure will cast a hw_device_t to audio_hw_device pointer in contexts + * where it's known the hw_device_t references an audio_hw_device. + */ + struct hw_device_t common; + + /** + * used by audio flinger to enumerate what devices are supported by + * each audio_hw_device implementation. + * + * Return value is a bitmask of 1 or more values of audio_devices_t + * + * NOTE: audio HAL implementations starting with + * AUDIO_DEVICE_API_VERSION_2_0 do not implement this function. + * All supported devices should be listed in audio_policy.conf + * file and the audio policy manager must choose the appropriate + * audio module based on information in this file. + */ + uint32_t (*get_supported_devices)(const struct audio_hw_device *dev); + + /** + * check to see if the audio hardware interface has been initialized. + * returns 0 on success, -ENODEV on failure. + */ + int (*init_check)(const struct audio_hw_device *dev); + + /** set the audio volume of a voice call. Range is between 0.0 and 1.0 */ + int (*set_voice_volume)(struct audio_hw_device *dev, float volume); + + /** + * set the audio volume for all audio activities other than voice call. + * Range between 0.0 and 1.0. If any value other than 0 is returned, + * the software mixer will emulate this capability. + */ + int (*set_master_volume)(struct audio_hw_device *dev, float volume); + + /** + * Get the current master volume value for the HAL, if the HAL supports + * master volume control. AudioFlinger will query this value from the + * primary audio HAL when the service starts and use the value for setting + * the initial master volume across all HALs. HALs which do not support + * this method may leave it set to NULL. + */ + int (*get_master_volume)(struct audio_hw_device *dev, float *volume); + + /** + * set_mode is called when the audio mode changes. AUDIO_MODE_NORMAL mode + * is for standard audio playback, AUDIO_MODE_RINGTONE when a ringtone is + * playing, and AUDIO_MODE_IN_CALL when a call is in progress. + */ + int (*set_mode)(struct audio_hw_device *dev, audio_mode_t mode); + + /* mic mute */ + int (*set_mic_mute)(struct audio_hw_device *dev, bool state); + int (*get_mic_mute)(const struct audio_hw_device *dev, bool *state); + + /* set/get global audio parameters */ + int (*set_parameters)(struct audio_hw_device *dev, const char *kv_pairs); + + /* + * Returns a pointer to a heap allocated string. The caller is responsible + * for freeing the memory for it using free(). + */ + char * (*get_parameters)(const struct audio_hw_device *dev, + const char *keys); + + /* Returns audio input buffer size according to parameters passed or + * 0 if one of the parameters is not supported. + * See also get_buffer_size which is for a particular stream. + */ + size_t (*get_input_buffer_size)(const struct audio_hw_device *dev, + const struct audio_config *config); + + /** This method creates and opens the audio hardware output stream. + * The "address" parameter qualifies the "devices" audio device type if needed. + * The format format depends on the device type: + * - Bluetooth devices use the MAC address of the device in the form "00:11:22:AA:BB:CC" + * - USB devices use the ALSA card and device numbers in the form "card=X;device=Y" + * - Other devices may use a number or any other string. + */ + + int (*open_output_stream)(struct audio_hw_device *dev, + audio_io_handle_t handle, + audio_devices_t devices, + audio_output_flags_t flags, + struct audio_config *config, + struct audio_stream_out **stream_out, + const char *address); + + void (*close_output_stream)(struct audio_hw_device *dev, + struct audio_stream_out* stream_out); + + /** This method creates and opens the audio hardware input stream */ + int (*open_input_stream)(struct audio_hw_device *dev, + audio_io_handle_t handle, + audio_devices_t devices, + struct audio_config *config, + struct audio_stream_in **stream_in, + audio_input_flags_t flags, + const char *address, + audio_source_t source); + + void (*close_input_stream)(struct audio_hw_device *dev, + struct audio_stream_in *stream_in); + + /** This method dumps the state of the audio hardware */ + int (*dump)(const struct audio_hw_device *dev, int fd); + + /** + * set the audio mute status for all audio activities. If any value other + * than 0 is returned, the software mixer will emulate this capability. + */ + int (*set_master_mute)(struct audio_hw_device *dev, bool mute); + + /** + * Get the current master mute status for the HAL, if the HAL supports + * master mute control. AudioFlinger will query this value from the primary + * audio HAL when the service starts and use the value for setting the + * initial master mute across all HALs. HALs which do not support this + * method may leave it set to NULL. + */ + int (*get_master_mute)(struct audio_hw_device *dev, bool *mute); + + /** + * Routing control + */ + + /* Creates an audio patch between several source and sink ports. + * The handle is allocated by the HAL and should be unique for this + * audio HAL module. */ + int (*create_audio_patch)(struct audio_hw_device *dev, + unsigned int num_sources, + const struct audio_port_config *sources, + unsigned int num_sinks, + const struct audio_port_config *sinks, + audio_patch_handle_t *handle); + + /* Release an audio patch */ + int (*release_audio_patch)(struct audio_hw_device *dev, + audio_patch_handle_t handle); + + /* Fills the list of supported attributes for a given audio port. + * As input, "port" contains the information (type, role, address etc...) + * needed by the HAL to identify the port. + * As output, "port" contains possible attributes (sampling rates, formats, + * channel masks, gain controllers...) for this port. + */ + int (*get_audio_port)(struct audio_hw_device *dev, + struct audio_port *port); + + /* Set audio port configuration */ + int (*set_audio_port_config)(struct audio_hw_device *dev, + const struct audio_port_config *config); + +#ifdef AUDIO_LISTEN_ENABLED + /** This method creates the listen session and returns handle */ + int (*open_listen_session)(struct audio_hw_device *dev, + listen_open_params_t *params, + struct listen_session** handle); + + /** This method closes the listen session */ + int (*close_listen_session)(struct audio_hw_device *dev, + struct listen_session* handle); + + /** This method sets the mad observer callback */ + int (*set_mad_observer)(struct audio_hw_device *dev, + listen_callback_t cb_func); + + /** + * This method is used for setting listen hal specfic parameters. + * If multiple paramets are set in one call and setting any one of them + * fails it will return failure. + */ + int (*listen_set_parameters)(struct audio_hw_device *dev, + const char *kv_pairs); +#endif +}; +typedef struct audio_hw_device audio_hw_device_t; + +/** convenience API for opening and closing a supported device */ + +static inline int audio_hw_device_open(const struct hw_module_t* module, + struct audio_hw_device** device) +{ + return module->methods->open(module, AUDIO_HARDWARE_INTERFACE, + (struct hw_device_t**)device); +} + +static inline int audio_hw_device_close(struct audio_hw_device* device) +{ + return device->common.close(&device->common); +} + + +__END_DECLS + +#endif // ANDROID_AUDIO_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/audio_alsaops.h b/third_party/android_hardware_libhardware/include/hardware/audio_alsaops.h new file mode 100644 index 00000000000000..0d266ff554b2b5 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/audio_alsaops.h @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* This file contains shared utility functions to handle the tinyalsa + * implementation for Android internal audio, generally in the hardware layer. + * Some routines may log a fatal error on failure, as noted. + */ + +#ifndef ANDROID_AUDIO_ALSAOPS_H +#define ANDROID_AUDIO_ALSAOPS_H + +#include +#include +#include + +__BEGIN_DECLS + +/* Converts audio_format to pcm_format. + * Parameters: + * format the audio_format_t to convert + * + * Logs a fatal error if format is not a valid convertible audio_format_t. + */ +static inline enum pcm_format pcm_format_from_audio_format(audio_format_t format) +{ + switch (format) { +#ifdef HAVE_BIG_ENDIAN + case AUDIO_FORMAT_PCM_16_BIT: + return PCM_FORMAT_S16_BE; + case AUDIO_FORMAT_PCM_24_BIT_PACKED: + return PCM_FORMAT_S24_3BE; + case AUDIO_FORMAT_PCM_32_BIT: + return PCM_FORMAT_S32_BE; + case AUDIO_FORMAT_PCM_8_24_BIT: + return PCM_FORMAT_S24_BE; +#else + case AUDIO_FORMAT_PCM_16_BIT: + return PCM_FORMAT_S16_LE; + case AUDIO_FORMAT_PCM_24_BIT_PACKED: + return PCM_FORMAT_S24_3LE; + case AUDIO_FORMAT_PCM_32_BIT: + return PCM_FORMAT_S32_LE; + case AUDIO_FORMAT_PCM_8_24_BIT: + return PCM_FORMAT_S24_LE; +#endif + case AUDIO_FORMAT_PCM_FLOAT: /* there is no equivalent for float */ + default: + LOG_ALWAYS_FATAL("pcm_format_from_audio_format: invalid audio format %#x", format); + return 0; + } +} + +/* Converts pcm_format to audio_format. + * Parameters: + * format the pcm_format to convert + * + * Logs a fatal error if format is not a valid convertible pcm_format. + */ +static inline audio_format_t audio_format_from_pcm_format(enum pcm_format format) +{ + switch (format) { +#ifdef HAVE_BIG_ENDIAN + case PCM_FORMAT_S16_BE: + return AUDIO_FORMAT_PCM_16_BIT; + case PCM_FORMAT_S24_3BE: + return AUDIO_FORMAT_PCM_24_BIT_PACKED; + case PCM_FORMAT_S24_BE: + return AUDIO_FORMAT_PCM_8_24_BIT; + case PCM_FORMAT_S32_BE: + return AUDIO_FORMAT_PCM_32_BIT; +#else + case PCM_FORMAT_S16_LE: + return AUDIO_FORMAT_PCM_16_BIT; + case PCM_FORMAT_S24_3LE: + return AUDIO_FORMAT_PCM_24_BIT_PACKED; + case PCM_FORMAT_S24_LE: + return AUDIO_FORMAT_PCM_8_24_BIT; + case PCM_FORMAT_S32_LE: + return AUDIO_FORMAT_PCM_32_BIT; +#endif + default: + LOG_ALWAYS_FATAL("audio_format_from_pcm_format: invalid pcm format %#x", format); + return 0; + } +} + +__END_DECLS + +#endif /* ANDROID_AUDIO_ALSAOPS_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/audio_amplifier.h b/third_party/android_hardware_libhardware/include/hardware/audio_amplifier.h new file mode 100644 index 00000000000000..e3477d52ad572b --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/audio_amplifier.h @@ -0,0 +1,144 @@ +/* + * Copyright (C) 2015, The CyanogenMod Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef CM_AUDIO_AMPLIFIER_INTERFACE_H +#define CM_AUDIO_AMPLIFIER_INTERFACE_H + +#include +#include +#include + +#include +#include + +#include + +__BEGIN_DECLS + +#define AMPLIFIER_HARDWARE_MODULE_ID "audio_amplifier" + +#define AMPLIFIER_HARDWARE_INTERFACE "audio_amplifier_hw_if" + +#define AMPLIFIER_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) + +#define AMPLIFIER_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define AMPLIFIER_DEVICE_API_VERSION_2_0 HARDWARE_DEVICE_API_VERSION(2, 0) +#define AMPLIFIER_DEVICE_API_VERSION_CURRENT AMPLIFIER_DEVICE_API_VERSION_2_0 + +struct str_parms; + +typedef struct amplifier_device { + /** + * Common methods of the amplifier device. This *must* be the first member + * of amplifier_device as users of this structure will cast a hw_device_t + * to amplifier_device pointer in contexts where it's known + * the hw_device_t references a amplifier_device. + */ + struct hw_device_t common; + + /** + * Notify amplifier device of current input devices + * + * This function should handle only input devices. + */ + int (*set_input_devices)(struct amplifier_device *device, uint32_t devices); + + /** + * Notify amplifier device of current output devices + * + * This function should handle only output devices. + */ + int (*set_output_devices)(struct amplifier_device *device, uint32_t devices); + + /** + * Notify amplifier device of output device enable/disable + * + * This function should handle only output devices. + */ + int (*enable_output_devices)(struct amplifier_device *device, + uint32_t devices, bool enable); + + /** + * Notify amplifier device of input device enable/disable + * + * This function should handle only input devices. + */ + int (*enable_input_devices)(struct amplifier_device *device, + uint32_t devices, bool enable); + + /** + * Notify amplifier device about current audio mode + */ + int (*set_mode)(struct amplifier_device *device, audio_mode_t mode); + + /** + * Notify amplifier device that an output stream has started + */ + int (*output_stream_start)(struct amplifier_device *device, + struct audio_stream_out *stream, bool offload); + + /** + * Notify amplifier device that an input stream has started + */ + int (*input_stream_start)(struct amplifier_device *device, + struct audio_stream_in *stream); + + /** + * Notify amplifier device that an output stream has stopped + */ + int (*output_stream_standby)(struct amplifier_device *device, + struct audio_stream_out *stream); + + /** + * Notify amplifier device that an input stream has stopped + */ + int (*input_stream_standby)(struct amplifier_device *device, + struct audio_stream_in *stream); + + /** + * set/get output audio device parameters. + */ + int (*set_parameters)(struct amplifier_device *device, + struct str_parms *parms); +} amplifier_device_t; + +typedef struct amplifier_module { + /** + * Common methods of the amplifier module. This *must* be the first member + * of amplifier_module as users of this structure will cast a hw_module_t + * to amplifier_module pointer in contexts where it's known + * the hw_module_t references a amplifier_module. + */ + struct hw_module_t common; +} amplifier_module_t; + +/** convenience API for opening and closing a supported device */ + +static inline int amplifier_device_open(const struct hw_module_t *module, + struct amplifier_device **device) +{ + return module->methods->open(module, AMPLIFIER_HARDWARE_INTERFACE, + (struct hw_device_t **) device); +} + +static inline int amplifier_device_close(struct amplifier_device *device) +{ + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // CM_AUDIO_AMPLIFIER_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/audio_effect.h b/third_party/android_hardware_libhardware/include/hardware/audio_effect.h new file mode 100644 index 00000000000000..41cd2e6146adc4 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/audio_effect.h @@ -0,0 +1,1014 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_AUDIO_EFFECT_H +#define ANDROID_AUDIO_EFFECT_H + +#include +#include +#include +#include +#include + +#include + +#include + + +__BEGIN_DECLS + + +///////////////////////////////////////////////// +// Common Definitions +///////////////////////////////////////////////// + +// +//--- Effect descriptor structure effect_descriptor_t +// + +// Unique effect ID (can be generated from the following site: +// http://www.itu.int/ITU-T/asn1/uuid.html) +// This format is used for both "type" and "uuid" fields of the effect descriptor structure. +// - When used for effect type and the engine is implementing and effect corresponding to a standard +// OpenSL ES interface, this ID must be the one defined in OpenSLES_IID.h for that interface. +// - When used as uuid, it should be a unique UUID for this particular implementation. +typedef struct effect_uuid_s { + uint32_t timeLow; + uint16_t timeMid; + uint16_t timeHiAndVersion; + uint16_t clockSeq; + uint8_t node[6]; +} effect_uuid_t; + +// Maximum length of character strings in structures defines by this API. +#define EFFECT_STRING_LEN_MAX 64 + +// NULL UUID definition (matches SL_IID_NULL_) +#define EFFECT_UUID_INITIALIZER { 0xec7178ec, 0xe5e1, 0x4432, 0xa3f4, \ + { 0x46, 0x57, 0xe6, 0x79, 0x52, 0x10 } } +static const effect_uuid_t EFFECT_UUID_NULL_ = EFFECT_UUID_INITIALIZER; +static const effect_uuid_t * const EFFECT_UUID_NULL = &EFFECT_UUID_NULL_; +static const char * const EFFECT_UUID_NULL_STR = "ec7178ec-e5e1-4432-a3f4-4657e6795210"; + + +// The effect descriptor contains necessary information to facilitate the enumeration of the effect +// engines present in a library. +typedef struct effect_descriptor_s { + effect_uuid_t type; // UUID of to the OpenSL ES interface implemented by this effect + effect_uuid_t uuid; // UUID for this particular implementation + uint32_t apiVersion; // Version of the effect control API implemented + uint32_t flags; // effect engine capabilities/requirements flags (see below) + uint16_t cpuLoad; // CPU load indication (see below) + uint16_t memoryUsage; // Data Memory usage (see below) + char name[EFFECT_STRING_LEN_MAX]; // human readable effect name + char implementor[EFFECT_STRING_LEN_MAX]; // human readable effect implementor name +} effect_descriptor_t; + +// CPU load and memory usage indication: each effect implementation must provide an indication of +// its CPU and memory usage for the audio effect framework to limit the number of effects +// instantiated at a given time on a given platform. +// The CPU load is expressed in 0.1 MIPS units as estimated on an ARM9E core (ARMv5TE) with 0 WS. +// The memory usage is expressed in KB and includes only dynamically allocated memory + +// Definitions for flags field of effect descriptor. +// +---------------------------+-----------+----------------------------------- +// | description | bits | values +// +---------------------------+-----------+----------------------------------- +// | connection mode | 0..2 | 0 insert: after track process +// | | | 1 auxiliary: connect to track auxiliary +// | | | output and use send level +// | | | 2 replace: replaces track process function; +// | | | must implement SRC, volume and mono to stereo. +// | | | 3 pre processing: applied below audio HAL on input +// | | | 4 post processing: applied below audio HAL on output +// | | | 5 - 7 reserved +// +---------------------------+-----------+----------------------------------- +// | insertion preference | 3..5 | 0 none +// | | | 1 first of the chain +// | | | 2 last of the chain +// | | | 3 exclusive (only effect in the insert chain) +// | | | 4..7 reserved +// +---------------------------+-----------+----------------------------------- +// | Volume management | 6..8 | 0 none +// | | | 1 implements volume control +// | | | 2 requires volume indication +// | | | 4 reserved +// +---------------------------+-----------+----------------------------------- +// | Device indication | 9..11 | 0 none +// | | | 1 requires device updates +// | | | 2, 4 reserved +// +---------------------------+-----------+----------------------------------- +// | Sample input mode | 12..13 | 1 direct: process() function or EFFECT_CMD_SET_CONFIG +// | | | command must specify a buffer descriptor +// | | | 2 provider: process() function uses the +// | | | bufferProvider indicated by the +// | | | EFFECT_CMD_SET_CONFIG command to request input. +// | | | buffers. +// | | | 3 both: both input modes are supported +// +---------------------------+-----------+----------------------------------- +// | Sample output mode | 14..15 | 1 direct: process() function or EFFECT_CMD_SET_CONFIG +// | | | command must specify a buffer descriptor +// | | | 2 provider: process() function uses the +// | | | bufferProvider indicated by the +// | | | EFFECT_CMD_SET_CONFIG command to request output +// | | | buffers. +// | | | 3 both: both output modes are supported +// +---------------------------+-----------+----------------------------------- +// | Hardware acceleration | 16..17 | 0 No hardware acceleration +// | | | 1 non tunneled hw acceleration: the process() function +// | | | reads the samples, send them to HW accelerated +// | | | effect processor, reads back the processed samples +// | | | and returns them to the output buffer. +// | | | 2 tunneled hw acceleration: the process() function is +// | | | transparent. The effect interface is only used to +// | | | control the effect engine. This mode is relevant for +// | | | global effects actually applied by the audio +// | | | hardware on the output stream. +// +---------------------------+-----------+----------------------------------- +// | Audio Mode indication | 18..19 | 0 none +// | | | 1 requires audio mode updates +// | | | 2..3 reserved +// +---------------------------+-----------+----------------------------------- +// | Audio source indication | 20..21 | 0 none +// | | | 1 requires audio source updates +// | | | 2..3 reserved +// +---------------------------+-----------+----------------------------------- +// | Effect offload supported | 22 | 0 The effect cannot be offloaded to an audio DSP +// | | | 1 The effect can be offloaded to an audio DSP +// +---------------------------+-----------+----------------------------------- + +// Insert mode +#define EFFECT_FLAG_TYPE_SHIFT 0 +#define EFFECT_FLAG_TYPE_SIZE 3 +#define EFFECT_FLAG_TYPE_MASK (((1 << EFFECT_FLAG_TYPE_SIZE) -1) \ + << EFFECT_FLAG_TYPE_SHIFT) +#define EFFECT_FLAG_TYPE_INSERT (0 << EFFECT_FLAG_TYPE_SHIFT) +#define EFFECT_FLAG_TYPE_AUXILIARY (1 << EFFECT_FLAG_TYPE_SHIFT) +#define EFFECT_FLAG_TYPE_REPLACE (2 << EFFECT_FLAG_TYPE_SHIFT) +#define EFFECT_FLAG_TYPE_PRE_PROC (3 << EFFECT_FLAG_TYPE_SHIFT) +#define EFFECT_FLAG_TYPE_POST_PROC (4 << EFFECT_FLAG_TYPE_SHIFT) + +// Insert preference +#define EFFECT_FLAG_INSERT_SHIFT (EFFECT_FLAG_TYPE_SHIFT + EFFECT_FLAG_TYPE_SIZE) +#define EFFECT_FLAG_INSERT_SIZE 3 +#define EFFECT_FLAG_INSERT_MASK (((1 << EFFECT_FLAG_INSERT_SIZE) -1) \ + << EFFECT_FLAG_INSERT_SHIFT) +#define EFFECT_FLAG_INSERT_ANY (0 << EFFECT_FLAG_INSERT_SHIFT) +#define EFFECT_FLAG_INSERT_FIRST (1 << EFFECT_FLAG_INSERT_SHIFT) +#define EFFECT_FLAG_INSERT_LAST (2 << EFFECT_FLAG_INSERT_SHIFT) +#define EFFECT_FLAG_INSERT_EXCLUSIVE (3 << EFFECT_FLAG_INSERT_SHIFT) + + +// Volume control +#define EFFECT_FLAG_VOLUME_SHIFT (EFFECT_FLAG_INSERT_SHIFT + EFFECT_FLAG_INSERT_SIZE) +#define EFFECT_FLAG_VOLUME_SIZE 3 +#define EFFECT_FLAG_VOLUME_MASK (((1 << EFFECT_FLAG_VOLUME_SIZE) -1) \ + << EFFECT_FLAG_VOLUME_SHIFT) +#define EFFECT_FLAG_VOLUME_CTRL (1 << EFFECT_FLAG_VOLUME_SHIFT) +#define EFFECT_FLAG_VOLUME_IND (2 << EFFECT_FLAG_VOLUME_SHIFT) +#define EFFECT_FLAG_VOLUME_NONE (0 << EFFECT_FLAG_VOLUME_SHIFT) + +// Device indication +#define EFFECT_FLAG_DEVICE_SHIFT (EFFECT_FLAG_VOLUME_SHIFT + EFFECT_FLAG_VOLUME_SIZE) +#define EFFECT_FLAG_DEVICE_SIZE 3 +#define EFFECT_FLAG_DEVICE_MASK (((1 << EFFECT_FLAG_DEVICE_SIZE) -1) \ + << EFFECT_FLAG_DEVICE_SHIFT) +#define EFFECT_FLAG_DEVICE_IND (1 << EFFECT_FLAG_DEVICE_SHIFT) +#define EFFECT_FLAG_DEVICE_NONE (0 << EFFECT_FLAG_DEVICE_SHIFT) + +// Sample input modes +#define EFFECT_FLAG_INPUT_SHIFT (EFFECT_FLAG_DEVICE_SHIFT + EFFECT_FLAG_DEVICE_SIZE) +#define EFFECT_FLAG_INPUT_SIZE 2 +#define EFFECT_FLAG_INPUT_MASK (((1 << EFFECT_FLAG_INPUT_SIZE) -1) \ + << EFFECT_FLAG_INPUT_SHIFT) +#define EFFECT_FLAG_INPUT_DIRECT (1 << EFFECT_FLAG_INPUT_SHIFT) +#define EFFECT_FLAG_INPUT_PROVIDER (2 << EFFECT_FLAG_INPUT_SHIFT) +#define EFFECT_FLAG_INPUT_BOTH (3 << EFFECT_FLAG_INPUT_SHIFT) + +// Sample output modes +#define EFFECT_FLAG_OUTPUT_SHIFT (EFFECT_FLAG_INPUT_SHIFT + EFFECT_FLAG_INPUT_SIZE) +#define EFFECT_FLAG_OUTPUT_SIZE 2 +#define EFFECT_FLAG_OUTPUT_MASK (((1 << EFFECT_FLAG_OUTPUT_SIZE) -1) \ + << EFFECT_FLAG_OUTPUT_SHIFT) +#define EFFECT_FLAG_OUTPUT_DIRECT (1 << EFFECT_FLAG_OUTPUT_SHIFT) +#define EFFECT_FLAG_OUTPUT_PROVIDER (2 << EFFECT_FLAG_OUTPUT_SHIFT) +#define EFFECT_FLAG_OUTPUT_BOTH (3 << EFFECT_FLAG_OUTPUT_SHIFT) + +// Hardware acceleration mode +#define EFFECT_FLAG_HW_ACC_SHIFT (EFFECT_FLAG_OUTPUT_SHIFT + EFFECT_FLAG_OUTPUT_SIZE) +#define EFFECT_FLAG_HW_ACC_SIZE 2 +#define EFFECT_FLAG_HW_ACC_MASK (((1 << EFFECT_FLAG_HW_ACC_SIZE) -1) \ + << EFFECT_FLAG_HW_ACC_SHIFT) +#define EFFECT_FLAG_HW_ACC_SIMPLE (1 << EFFECT_FLAG_HW_ACC_SHIFT) +#define EFFECT_FLAG_HW_ACC_TUNNEL (2 << EFFECT_FLAG_HW_ACC_SHIFT) + +// Audio mode indication +#define EFFECT_FLAG_AUDIO_MODE_SHIFT (EFFECT_FLAG_HW_ACC_SHIFT + EFFECT_FLAG_HW_ACC_SIZE) +#define EFFECT_FLAG_AUDIO_MODE_SIZE 2 +#define EFFECT_FLAG_AUDIO_MODE_MASK (((1 << EFFECT_FLAG_AUDIO_MODE_SIZE) -1) \ + << EFFECT_FLAG_AUDIO_MODE_SHIFT) +#define EFFECT_FLAG_AUDIO_MODE_IND (1 << EFFECT_FLAG_AUDIO_MODE_SHIFT) +#define EFFECT_FLAG_AUDIO_MODE_NONE (0 << EFFECT_FLAG_AUDIO_MODE_SHIFT) + +// Audio source indication +#define EFFECT_FLAG_AUDIO_SOURCE_SHIFT (EFFECT_FLAG_AUDIO_MODE_SHIFT + EFFECT_FLAG_AUDIO_MODE_SIZE) +#define EFFECT_FLAG_AUDIO_SOURCE_SIZE 2 +#define EFFECT_FLAG_AUDIO_SOURCE_MASK (((1 << EFFECT_FLAG_AUDIO_SOURCE_SIZE) -1) \ + << EFFECT_FLAG_AUDIO_SOURCE_SHIFT) +#define EFFECT_FLAG_AUDIO_SOURCE_IND (1 << EFFECT_FLAG_AUDIO_SOURCE_SHIFT) +#define EFFECT_FLAG_AUDIO_SOURCE_NONE (0 << EFFECT_FLAG_AUDIO_SOURCE_SHIFT) + +// Effect offload indication +#define EFFECT_FLAG_OFFLOAD_SHIFT (EFFECT_FLAG_AUDIO_SOURCE_SHIFT + \ + EFFECT_FLAG_AUDIO_SOURCE_SIZE) +#define EFFECT_FLAG_OFFLOAD_SIZE 1 +#define EFFECT_FLAG_OFFLOAD_MASK (((1 << EFFECT_FLAG_OFFLOAD_SIZE) -1) \ + << EFFECT_FLAG_OFFLOAD_SHIFT) +#define EFFECT_FLAG_OFFLOAD_SUPPORTED (1 << EFFECT_FLAG_OFFLOAD_SHIFT) + +#define EFFECT_MAKE_API_VERSION(M, m) (((M)<<16) | ((m) & 0xFFFF)) +#define EFFECT_API_VERSION_MAJOR(v) ((v)>>16) +#define EFFECT_API_VERSION_MINOR(v) ((m) & 0xFFFF) + + + +///////////////////////////////////////////////// +// Effect control interface +///////////////////////////////////////////////// + +// Effect control interface version 2.0 +#define EFFECT_CONTROL_API_VERSION EFFECT_MAKE_API_VERSION(2,0) + +// Effect control interface structure: effect_interface_s +// The effect control interface is exposed by each effect engine implementation. It consists of +// a set of functions controlling the configuration, activation and process of the engine. +// The functions are grouped in a structure of type effect_interface_s. +// +// Effect control interface handle: effect_handle_t +// The effect_handle_t serves two purposes regarding the implementation of the effect engine: +// - 1 it is the address of a pointer to an effect_interface_s structure where the functions +// of the effect control API for a particular effect are located. +// - 2 it is the address of the context of a particular effect instance. +// A typical implementation in the effect library would define a structure as follows: +// struct effect_module_s { +// const struct effect_interface_s *itfe; +// effect_config_t config; +// effect_context_t context; +// } +// The implementation of EffectCreate() function would then allocate a structure of this +// type and return its address as effect_handle_t +typedef struct effect_interface_s **effect_handle_t; + + +// Forward definition of type audio_buffer_t +typedef struct audio_buffer_s audio_buffer_t; + + + + + + +// Effect control interface definition +struct effect_interface_s { + //////////////////////////////////////////////////////////////////////////////// + // + // Function: process + // + // Description: Effect process function. Takes input samples as specified + // (count and location) in input buffer descriptor and output processed + // samples as specified in output buffer descriptor. If the buffer descriptor + // is not specified the function must use either the buffer or the + // buffer provider function installed by the EFFECT_CMD_SET_CONFIG command. + // The effect framework will call the process() function after the EFFECT_CMD_ENABLE + // command is received and until the EFFECT_CMD_DISABLE is received. When the engine + // receives the EFFECT_CMD_DISABLE command it should turn off the effect gracefully + // and when done indicate that it is OK to stop calling the process() function by + // returning the -ENODATA status. + // + // NOTE: the process() function implementation should be "real-time safe" that is + // it should not perform blocking calls: malloc/free, sleep, read/write/open/close, + // pthread_cond_wait/pthread_mutex_lock... + // + // Input: + // self: handle to the effect interface this function + // is called on. + // inBuffer: buffer descriptor indicating where to read samples to process. + // If NULL, use the configuration passed by EFFECT_CMD_SET_CONFIG command. + // + // outBuffer: buffer descriptor indicating where to write processed samples. + // If NULL, use the configuration passed by EFFECT_CMD_SET_CONFIG command. + // + // Output: + // returned value: 0 successful operation + // -ENODATA the engine has finished the disable phase and the framework + // can stop calling process() + // -EINVAL invalid interface handle or + // invalid input/output buffer description + //////////////////////////////////////////////////////////////////////////////// + int32_t (*process)(effect_handle_t self, + audio_buffer_t *inBuffer, + audio_buffer_t *outBuffer); + //////////////////////////////////////////////////////////////////////////////// + // + // Function: command + // + // Description: Send a command and receive a response to/from effect engine. + // + // Input: + // self: handle to the effect interface this function + // is called on. + // cmdCode: command code: the command can be a standardized command defined in + // effect_command_e (see below) or a proprietary command. + // cmdSize: size of command in bytes + // pCmdData: pointer to command data + // pReplyData: pointer to reply data + // + // Input/Output: + // replySize: maximum size of reply data as input + // actual size of reply data as output + // + // Output: + // returned value: 0 successful operation + // -EINVAL invalid interface handle or + // invalid command/reply size or format according to + // command code + // The return code should be restricted to indicate problems related to this API + // specification. Status related to the execution of a particular command should be + // indicated as part of the reply field. + // + // *pReplyData updated with command response + // + //////////////////////////////////////////////////////////////////////////////// + int32_t (*command)(effect_handle_t self, + uint32_t cmdCode, + uint32_t cmdSize, + void *pCmdData, + uint32_t *replySize, + void *pReplyData); + //////////////////////////////////////////////////////////////////////////////// + // + // Function: get_descriptor + // + // Description: Returns the effect descriptor + // + // Input: + // self: handle to the effect interface this function + // is called on. + // + // Input/Output: + // pDescriptor: address where to return the effect descriptor. + // + // Output: + // returned value: 0 successful operation. + // -EINVAL invalid interface handle or invalid pDescriptor + // *pDescriptor: updated with the effect descriptor. + // + //////////////////////////////////////////////////////////////////////////////// + int32_t (*get_descriptor)(effect_handle_t self, + effect_descriptor_t *pDescriptor); + //////////////////////////////////////////////////////////////////////////////// + // + // Function: process_reverse + // + // Description: Process reverse stream function. This function is used to pass + // a reference stream to the effect engine. If the engine does not need a reference + // stream, this function pointer can be set to NULL. + // This function would typically implemented by an Echo Canceler. + // + // Input: + // self: handle to the effect interface this function + // is called on. + // inBuffer: buffer descriptor indicating where to read samples to process. + // If NULL, use the configuration passed by EFFECT_CMD_SET_CONFIG_REVERSE command. + // + // outBuffer: buffer descriptor indicating where to write processed samples. + // If NULL, use the configuration passed by EFFECT_CMD_SET_CONFIG_REVERSE command. + // If the buffer and buffer provider in the configuration received by + // EFFECT_CMD_SET_CONFIG_REVERSE are also NULL, do not return modified reverse + // stream data + // + // Output: + // returned value: 0 successful operation + // -ENODATA the engine has finished the disable phase and the framework + // can stop calling process_reverse() + // -EINVAL invalid interface handle or + // invalid input/output buffer description + //////////////////////////////////////////////////////////////////////////////// + int32_t (*process_reverse)(effect_handle_t self, + audio_buffer_t *inBuffer, + audio_buffer_t *outBuffer); +}; + + +// +//--- Standardized command codes for command() function +// +enum effect_command_e { + EFFECT_CMD_INIT, // initialize effect engine + EFFECT_CMD_SET_CONFIG, // configure effect engine (see effect_config_t) + EFFECT_CMD_RESET, // reset effect engine + EFFECT_CMD_ENABLE, // enable effect process + EFFECT_CMD_DISABLE, // disable effect process + EFFECT_CMD_SET_PARAM, // set parameter immediately (see effect_param_t) + EFFECT_CMD_SET_PARAM_DEFERRED, // set parameter deferred + EFFECT_CMD_SET_PARAM_COMMIT, // commit previous set parameter deferred + EFFECT_CMD_GET_PARAM, // get parameter + EFFECT_CMD_SET_DEVICE, // set audio device (see audio.h, audio_devices_t) + EFFECT_CMD_SET_VOLUME, // set volume + EFFECT_CMD_SET_AUDIO_MODE, // set the audio mode (normal, ring, ...) + EFFECT_CMD_SET_CONFIG_REVERSE, // configure effect engine reverse stream(see effect_config_t) + EFFECT_CMD_SET_INPUT_DEVICE, // set capture device (see audio.h, audio_devices_t) + EFFECT_CMD_GET_CONFIG, // read effect engine configuration + EFFECT_CMD_GET_CONFIG_REVERSE, // read configure effect engine reverse stream configuration + EFFECT_CMD_GET_FEATURE_SUPPORTED_CONFIGS,// get all supported configurations for a feature. + EFFECT_CMD_GET_FEATURE_CONFIG, // get current feature configuration + EFFECT_CMD_SET_FEATURE_CONFIG, // set current feature configuration + EFFECT_CMD_SET_AUDIO_SOURCE, // set the audio source (see audio.h, audio_source_t) + EFFECT_CMD_OFFLOAD, // set if effect thread is an offload one, + // send the ioHandle of the effect thread + EFFECT_CMD_FIRST_PROPRIETARY = 0x10000 // first proprietary command code +}; + +//================================================================================================== +// command: EFFECT_CMD_INIT +//-------------------------------------------------------------------------------------------------- +// description: +// Initialize effect engine: All configurations return to default +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_SET_CONFIG +//-------------------------------------------------------------------------------------------------- +// description: +// Apply new audio parameters configurations for input and output buffers +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_config_t) +// data: effect_config_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_RESET +//-------------------------------------------------------------------------------------------------- +// description: +// Reset the effect engine. Keep configuration but resets state and buffer content +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_ENABLE +//-------------------------------------------------------------------------------------------------- +// description: +// Enable the process. Called by the framework before the first call to process() +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_DISABLE +//-------------------------------------------------------------------------------------------------- +// description: +// Disable the process. Called by the framework after the last call to process() +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_SET_PARAM +//-------------------------------------------------------------------------------------------------- +// description: +// Set a parameter and apply it immediately +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_param_t) + size of param and value +// data: effect_param_t + param + value. See effect_param_t definition below for value offset +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_SET_PARAM_DEFERRED +//-------------------------------------------------------------------------------------------------- +// description: +// Set a parameter but apply it only when receiving EFFECT_CMD_SET_PARAM_COMMIT command +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_param_t) + size of param and value +// data: effect_param_t + param + value. See effect_param_t definition below for value offset +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_SET_PARAM_COMMIT +//-------------------------------------------------------------------------------------------------- +// description: +// Apply all previously received EFFECT_CMD_SET_PARAM_DEFERRED commands +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_GET_PARAM +//-------------------------------------------------------------------------------------------------- +// description: +// Get a parameter value +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_param_t) + size of param +// data: effect_param_t + param +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(effect_param_t) + size of param and value +// data: effect_param_t + param + value. See effect_param_t definition below for value offset +//================================================================================================== +// command: EFFECT_CMD_SET_DEVICE +//-------------------------------------------------------------------------------------------------- +// description: +// Set the rendering device the audio output path is connected to. See audio.h, audio_devices_t +// for device values. +// The effect implementation must set EFFECT_FLAG_DEVICE_IND flag in its descriptor to receive this +// command when the device changes +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) +// data: uint32_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_SET_VOLUME +//-------------------------------------------------------------------------------------------------- +// description: +// Set and get volume. Used by audio framework to delegate volume control to effect engine. +// The effect implementation must set EFFECT_FLAG_VOLUME_IND or EFFECT_FLAG_VOLUME_CTRL flag in +// its descriptor to receive this command before every call to process() function +// If EFFECT_FLAG_VOLUME_CTRL flag is set in the effect descriptor, the effect engine must return +// the volume that should be applied before the effect is processed. The overall volume (the volume +// actually applied by the effect engine multiplied by the returned value) should match the value +// indicated in the command. +//-------------------------------------------------------------------------------------------------- +// command format: +// size: n * sizeof(uint32_t) +// data: volume for each channel defined in effect_config_t for output buffer expressed in +// 8.24 fixed point format +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: n * sizeof(uint32_t) / 0 +// data: - if EFFECT_FLAG_VOLUME_CTRL is set in effect descriptor: +// volume for each channel defined in effect_config_t for output buffer expressed in +// 8.24 fixed point format +// - if EFFECT_FLAG_VOLUME_CTRL is not set in effect descriptor: +// N/A +// It is legal to receive a null pointer as pReplyData in which case the effect framework has +// delegated volume control to another effect +//================================================================================================== +// command: EFFECT_CMD_SET_AUDIO_MODE +//-------------------------------------------------------------------------------------------------- +// description: +// Set the audio mode. The effect implementation must set EFFECT_FLAG_AUDIO_MODE_IND flag in its +// descriptor to receive this command when the audio mode changes. +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) +// data: audio_mode_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_SET_CONFIG_REVERSE +//-------------------------------------------------------------------------------------------------- +// description: +// Apply new audio parameters configurations for input and output buffers of reverse stream. +// An example of reverse stream is the echo reference supplied to an Acoustic Echo Canceler. +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_config_t) +// data: effect_config_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(int) +// data: status +//================================================================================================== +// command: EFFECT_CMD_SET_INPUT_DEVICE +//-------------------------------------------------------------------------------------------------- +// description: +// Set the capture device the audio input path is connected to. See audio.h, audio_devices_t +// for device values. +// The effect implementation must set EFFECT_FLAG_DEVICE_IND flag in its descriptor to receive this +// command when the device changes +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) +// data: uint32_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_GET_CONFIG +//-------------------------------------------------------------------------------------------------- +// description: +// Read audio parameters configurations for input and output buffers +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(effect_config_t) +// data: effect_config_t +//================================================================================================== +// command: EFFECT_CMD_GET_CONFIG_REVERSE +//-------------------------------------------------------------------------------------------------- +// description: +// Read audio parameters configurations for input and output buffers of reverse stream +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 0 +// data: N/A +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(effect_config_t) +// data: effect_config_t +//================================================================================================== +// command: EFFECT_CMD_GET_FEATURE_SUPPORTED_CONFIGS +//-------------------------------------------------------------------------------------------------- +// description: +// Queries for supported configurations for a particular feature (e.g. get the supported +// combinations of main and auxiliary channels for a noise suppressor). +// The command parameter is the feature identifier (See effect_feature_e for a list of defined +// features) followed by the maximum number of configuration descriptor to return. +// The reply is composed of: +// - status (uint32_t): +// - 0 if feature is supported +// - -ENOSYS if the feature is not supported, +// - -ENOMEM if the feature is supported but the total number of supported configurations +// exceeds the maximum number indicated by the caller. +// - total number of supported configurations (uint32_t) +// - an array of configuration descriptors. +// The actual number of descriptors returned must not exceed the maximum number indicated by +// the caller. +//-------------------------------------------------------------------------------------------------- +// command format: +// size: 2 x sizeof(uint32_t) +// data: effect_feature_e + maximum number of configurations to return +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 2 x sizeof(uint32_t) + n x sizeof () +// data: status + total number of configurations supported + array of n config descriptors +//================================================================================================== +// command: EFFECT_CMD_GET_FEATURE_CONFIG +//-------------------------------------------------------------------------------------------------- +// description: +// Retrieves current configuration for a given feature. +// The reply status is: +// - 0 if feature is supported +// - -ENOSYS if the feature is not supported, +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) +// data: effect_feature_e +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(uint32_t) + sizeof () +// data: status + config descriptor +//================================================================================================== +// command: EFFECT_CMD_SET_FEATURE_CONFIG +//-------------------------------------------------------------------------------------------------- +// description: +// Sets current configuration for a given feature. +// The reply status is: +// - 0 if feature is supported +// - -ENOSYS if the feature is not supported, +// - -EINVAL if the configuration is invalid +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) + sizeof () +// data: effect_feature_e + config descriptor +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(uint32_t) +// data: status +//================================================================================================== +// command: EFFECT_CMD_SET_AUDIO_SOURCE +//-------------------------------------------------------------------------------------------------- +// description: +// Set the audio source the capture path is configured for (Camcorder, voice recognition...). +// See audio.h, audio_source_t for values. +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(uint32_t) +// data: uint32_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: 0 +// data: N/A +//================================================================================================== +// command: EFFECT_CMD_OFFLOAD +//-------------------------------------------------------------------------------------------------- +// description: +// 1.indicate if the playback thread the effect is attached to is offloaded or not +// 2.update the io handle of the playback thread the effect is attached to +//-------------------------------------------------------------------------------------------------- +// command format: +// size: sizeof(effect_offload_param_t) +// data: effect_offload_param_t +//-------------------------------------------------------------------------------------------------- +// reply format: +// size: sizeof(uint32_t) +// data: uint32_t +//-------------------------------------------------------------------------------------------------- +// command: EFFECT_CMD_FIRST_PROPRIETARY +//-------------------------------------------------------------------------------------------------- +// description: +// All proprietary effect commands must use command codes above this value. The size and format of +// command and response fields is free in this case +//================================================================================================== + + +// Audio buffer descriptor used by process(), bufferProvider() functions and buffer_config_t +// structure. Multi-channel audio is always interleaved. The channel order is from LSB to MSB with +// regard to the channel mask definition in audio.h, audio_channel_mask_t e.g : +// Stereo: left, right +// 5 point 1: front left, front right, front center, low frequency, back left, back right +// The buffer size is expressed in frame count, a frame being composed of samples for all +// channels at a given time. Frame size for unspecified format (AUDIO_FORMAT_OTHER) is 8 bit by +// definition +struct audio_buffer_s { + size_t frameCount; // number of frames in buffer + union { + void* raw; // raw pointer to start of buffer + int32_t* s32; // pointer to signed 32 bit data at start of buffer + int16_t* s16; // pointer to signed 16 bit data at start of buffer + uint8_t* u8; // pointer to unsigned 8 bit data at start of buffer + }; +}; + +// The buffer_provider_s structure contains functions that can be used +// by the effect engine process() function to query and release input +// or output audio buffer. +// The getBuffer() function is called to retrieve a buffer where data +// should read from or written to by process() function. +// The releaseBuffer() function MUST be called when the buffer retrieved +// with getBuffer() is not needed anymore. +// The process function should use the buffer provider mechanism to retrieve +// input or output buffer if the inBuffer or outBuffer passed as argument is NULL +// and the buffer configuration (buffer_config_t) given by the EFFECT_CMD_SET_CONFIG +// command did not specify an audio buffer. + +typedef int32_t (* buffer_function_t)(void *cookie, audio_buffer_t *buffer); + +typedef struct buffer_provider_s { + buffer_function_t getBuffer; // retrieve next buffer + buffer_function_t releaseBuffer; // release used buffer + void *cookie; // for use by client of buffer provider functions +} buffer_provider_t; + + +// The buffer_config_s structure specifies the input or output audio format +// to be used by the effect engine. It is part of the effect_config_t +// structure that defines both input and output buffer configurations and is +// passed by the EFFECT_CMD_SET_CONFIG or EFFECT_CMD_SET_CONFIG_REVERSE command. +typedef struct buffer_config_s { + audio_buffer_t buffer; // buffer for use by process() function if not passed explicitly + uint32_t samplingRate; // sampling rate + uint32_t channels; // channel mask (see audio_channel_mask_t in audio.h) + buffer_provider_t bufferProvider; // buffer provider + uint8_t format; // Audio format (see audio_format_t in audio.h) + uint8_t accessMode; // read/write or accumulate in buffer (effect_buffer_access_e) + uint16_t mask; // indicates which of the above fields is valid +} buffer_config_t; + +// Values for "accessMode" field of buffer_config_t: +// overwrite, read only, accumulate (read/modify/write) +enum effect_buffer_access_e { + EFFECT_BUFFER_ACCESS_WRITE, + EFFECT_BUFFER_ACCESS_READ, + EFFECT_BUFFER_ACCESS_ACCUMULATE + +}; + +// feature identifiers for EFFECT_CMD_GET_FEATURE_SUPPORTED_CONFIGS command +enum effect_feature_e { + EFFECT_FEATURE_AUX_CHANNELS, // supports auxiliary channels (e.g. dual mic noise suppressor) + EFFECT_FEATURE_CNT +}; + +// EFFECT_FEATURE_AUX_CHANNELS feature configuration descriptor. Describe a combination +// of main and auxiliary channels supported +typedef struct channel_config_s { + audio_channel_mask_t main_channels; // channel mask for main channels + audio_channel_mask_t aux_channels; // channel mask for auxiliary channels +} channel_config_t; + + +// Values for bit field "mask" in buffer_config_t. If a bit is set, the corresponding field +// in buffer_config_t must be taken into account when executing the EFFECT_CMD_SET_CONFIG command +#define EFFECT_CONFIG_BUFFER 0x0001 // buffer field must be taken into account +#define EFFECT_CONFIG_SMP_RATE 0x0002 // samplingRate field must be taken into account +#define EFFECT_CONFIG_CHANNELS 0x0004 // channels field must be taken into account +#define EFFECT_CONFIG_FORMAT 0x0008 // format field must be taken into account +#define EFFECT_CONFIG_ACC_MODE 0x0010 // accessMode field must be taken into account +#define EFFECT_CONFIG_PROVIDER 0x0020 // bufferProvider field must be taken into account +#define EFFECT_CONFIG_ALL (EFFECT_CONFIG_BUFFER | EFFECT_CONFIG_SMP_RATE | \ + EFFECT_CONFIG_CHANNELS | EFFECT_CONFIG_FORMAT | \ + EFFECT_CONFIG_ACC_MODE | EFFECT_CONFIG_PROVIDER) + + +// effect_config_s structure describes the format of the pCmdData argument of EFFECT_CMD_SET_CONFIG +// command to configure audio parameters and buffers for effect engine input and output. +typedef struct effect_config_s { + buffer_config_t inputCfg; + buffer_config_t outputCfg; +} effect_config_t; + + +// effect_param_s structure describes the format of the pCmdData argument of EFFECT_CMD_SET_PARAM +// command and pCmdData and pReplyData of EFFECT_CMD_GET_PARAM command. +// psize and vsize represent the actual size of parameter and value. +// +// NOTE: the start of value field inside the data field is always on a 32 bit boundary: +// +// +-----------+ +// | status | sizeof(int) +// +-----------+ +// | psize | sizeof(int) +// +-----------+ +// | vsize | sizeof(int) +// +-----------+ +// | | | | +// ~ parameter ~ > psize | +// | | | > ((psize - 1)/sizeof(int) + 1) * sizeof(int) +// +-----------+ | +// | padding | | +// +-----------+ +// | | | +// ~ value ~ > vsize +// | | | +// +-----------+ + +typedef struct effect_param_s { + int32_t status; // Transaction status (unused for command, used for reply) + uint32_t psize; // Parameter size + uint32_t vsize; // Value size + char data[]; // Start of Parameter + Value data +} effect_param_t; + +// structure used by EFFECT_CMD_OFFLOAD command +typedef struct effect_offload_param_s { + bool isOffload; // true if the playback thread the effect is attached to is offloaded + int ioHandle; // io handle of the playback thread the effect is attached to +} effect_offload_param_t; + + +///////////////////////////////////////////////// +// Effect library interface +///////////////////////////////////////////////// + +// Effect library interface version 3.0 +// Note that EffectsFactory.c only checks the major version component, so changes to the minor +// number can only be used for fully backwards compatible changes +#define EFFECT_LIBRARY_API_VERSION EFFECT_MAKE_API_VERSION(3,0) + +#define AUDIO_EFFECT_LIBRARY_TAG ((('A') << 24) | (('E') << 16) | (('L') << 8) | ('T')) + +// Every effect library must have a data structure named AUDIO_EFFECT_LIBRARY_INFO_SYM +// and the fields of this data structure must begin with audio_effect_library_t + +typedef struct audio_effect_library_s { + // tag must be initialized to AUDIO_EFFECT_LIBRARY_TAG + uint32_t tag; + // Version of the effect library API : 0xMMMMmmmm MMMM: Major, mmmm: minor + uint32_t version; + // Name of this library + const char *name; + // Author/owner/implementor of the library + const char *implementor; + + //////////////////////////////////////////////////////////////////////////////// + // + // Function: create_effect + // + // Description: Creates an effect engine of the specified implementation uuid and + // returns an effect control interface on this engine. The function will allocate the + // resources for an instance of the requested effect engine and return + // a handle on the effect control interface. + // + // Input: + // uuid: pointer to the effect uuid. + // sessionId: audio session to which this effect instance will be attached. + // All effects created with the same session ID are connected in series and process + // the same signal stream. Knowing that two effects are part of the same effect + // chain can help the library implement some kind of optimizations. + // ioId: identifies the output or input stream this effect is directed to in + // audio HAL. + // For future use especially with tunneled HW accelerated effects + // + // Input/Output: + // pHandle: address where to return the effect interface handle. + // + // Output: + // returned value: 0 successful operation. + // -ENODEV library failed to initialize + // -EINVAL invalid pEffectUuid or pHandle + // -ENOENT no effect with this uuid found + // *pHandle: updated with the effect interface handle. + // + //////////////////////////////////////////////////////////////////////////////// + int32_t (*create_effect)(const effect_uuid_t *uuid, + int32_t sessionId, + int32_t ioId, + effect_handle_t *pHandle); + + //////////////////////////////////////////////////////////////////////////////// + // + // Function: release_effect + // + // Description: Releases the effect engine whose handle is given as argument. + // All resources allocated to this particular instance of the effect are + // released. + // + // Input: + // handle: handle on the effect interface to be released. + // + // Output: + // returned value: 0 successful operation. + // -ENODEV library failed to initialize + // -EINVAL invalid interface handle + // + //////////////////////////////////////////////////////////////////////////////// + int32_t (*release_effect)(effect_handle_t handle); + + //////////////////////////////////////////////////////////////////////////////// + // + // Function: get_descriptor + // + // Description: Returns the descriptor of the effect engine which implementation UUID is + // given as argument. + // + // Input/Output: + // uuid: pointer to the effect uuid. + // pDescriptor: address where to return the effect descriptor. + // + // Output: + // returned value: 0 successful operation. + // -ENODEV library failed to initialize + // -EINVAL invalid pDescriptor or uuid + // *pDescriptor: updated with the effect descriptor. + // + //////////////////////////////////////////////////////////////////////////////// + int32_t (*get_descriptor)(const effect_uuid_t *uuid, + effect_descriptor_t *pDescriptor); +} audio_effect_library_t; + +// Name of the hal_module_info +#define AUDIO_EFFECT_LIBRARY_INFO_SYM AELI + +// Name of the hal_module_info as a string +#define AUDIO_EFFECT_LIBRARY_INFO_SYM_AS_STR "AELI" + +__END_DECLS + +#endif // ANDROID_AUDIO_EFFECT_H diff --git a/third_party/android_hardware_libhardware/include/hardware/audio_policy.h b/third_party/android_hardware_libhardware/include/hardware/audio_policy.h new file mode 100644 index 00000000000000..99cb0449fba4c3 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/audio_policy.h @@ -0,0 +1,457 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_AUDIO_POLICY_INTERFACE_H +#define ANDROID_AUDIO_POLICY_INTERFACE_H + +#include +#include +#include + +#include + +#include +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define AUDIO_POLICY_HARDWARE_MODULE_ID "audio_policy" + +/** + * Name of the audio devices to open + */ +#define AUDIO_POLICY_INTERFACE "policy" + +/* ---------------------------------------------------------------------------- */ + +/* + * The audio_policy and audio_policy_service_ops structs define the + * communication interfaces between the platform specific audio policy manager + * and Android generic audio policy manager. + * The platform specific audio policy manager must implement methods of the + * audio_policy struct. + * This implementation makes use of the audio_policy_service_ops to control + * the activity and configuration of audio input and output streams. + * + * The platform specific audio policy manager is in charge of the audio + * routing and volume control policies for a given platform. + * The main roles of this module are: + * - keep track of current system state (removable device connections, phone + * state, user requests...). + * System state changes and user actions are notified to audio policy + * manager with methods of the audio_policy. + * + * - process get_output() queries received when AudioTrack objects are + * created: Those queries return a handler on an output that has been + * selected, configured and opened by the audio policy manager and that + * must be used by the AudioTrack when registering to the AudioFlinger + * with the createTrack() method. + * When the AudioTrack object is released, a release_output() query + * is received and the audio policy manager can decide to close or + * reconfigure the output depending on other streams using this output and + * current system state. + * + * - similarly process get_input() and release_input() queries received from + * AudioRecord objects and configure audio inputs. + * - process volume control requests: the stream volume is converted from + * an index value (received from UI) to a float value applicable to each + * output as a function of platform specific settings and current output + * route (destination device). It also make sure that streams are not + * muted if not allowed (e.g. camera shutter sound in some countries). + */ + +/* XXX: this should be defined OUTSIDE of frameworks/base */ +struct effect_descriptor_s; + +struct audio_policy { + /* + * configuration functions + */ + + /* indicate a change in device connection status */ + int (*set_device_connection_state)(struct audio_policy *pol, + audio_devices_t device, + audio_policy_dev_state_t state, + const char *device_address); + + /* retrieve a device connection status */ + audio_policy_dev_state_t (*get_device_connection_state)( + const struct audio_policy *pol, + audio_devices_t device, + const char *device_address); + + /* indicate a change in phone state. Valid phones states are defined + * by audio_mode_t */ + void (*set_phone_state)(struct audio_policy *pol, audio_mode_t state); + + /* deprecated, never called (was "indicate a change in ringer mode") */ + void (*set_ringer_mode)(struct audio_policy *pol, uint32_t mode, + uint32_t mask); + + /* force using a specific device category for the specified usage */ + void (*set_force_use)(struct audio_policy *pol, + audio_policy_force_use_t usage, + audio_policy_forced_cfg_t config); + + /* retrieve current device category forced for a given usage */ + audio_policy_forced_cfg_t (*get_force_use)(const struct audio_policy *pol, + audio_policy_force_use_t usage); + + /* if can_mute is true, then audio streams that are marked ENFORCED_AUDIBLE + * can still be muted. */ + void (*set_can_mute_enforced_audible)(struct audio_policy *pol, + bool can_mute); + + /* check proper initialization */ + int (*init_check)(const struct audio_policy *pol); + + /* + * Audio routing query functions + */ + + /* request an output appropriate for playback of the supplied stream type and + * parameters */ + audio_io_handle_t (*get_output)(struct audio_policy *pol, + audio_stream_type_t stream, + uint32_t samplingRate, + audio_format_t format, + audio_channel_mask_t channelMask, + audio_output_flags_t flags, + const audio_offload_info_t *offloadInfo); + + /* indicates to the audio policy manager that the output starts being used + * by corresponding stream. */ + int (*start_output)(struct audio_policy *pol, + audio_io_handle_t output, + audio_stream_type_t stream, + int session); + + /* indicates to the audio policy manager that the output stops being used + * by corresponding stream. */ + int (*stop_output)(struct audio_policy *pol, + audio_io_handle_t output, + audio_stream_type_t stream, + int session); + + /* releases the output. */ + void (*release_output)(struct audio_policy *pol, audio_io_handle_t output); + + /* request an input appropriate for record from the supplied device with + * supplied parameters. */ + audio_io_handle_t (*get_input)(struct audio_policy *pol, audio_source_t inputSource, + uint32_t samplingRate, + audio_format_t format, + audio_channel_mask_t channelMask, + audio_in_acoustics_t acoustics); + + /* indicates to the audio policy manager that the input starts being used */ + int (*start_input)(struct audio_policy *pol, audio_io_handle_t input); + + /* indicates to the audio policy manager that the input stops being used. */ + int (*stop_input)(struct audio_policy *pol, audio_io_handle_t input); + + /* releases the input. */ + void (*release_input)(struct audio_policy *pol, audio_io_handle_t input); + + /* + * volume control functions + */ + + /* initialises stream volume conversion parameters by specifying volume + * index range. The index range for each stream is defined by AudioService. */ + void (*init_stream_volume)(struct audio_policy *pol, + audio_stream_type_t stream, + int index_min, + int index_max); + + /* sets the new stream volume at a level corresponding to the supplied + * index. The index is within the range specified by init_stream_volume() */ + int (*set_stream_volume_index)(struct audio_policy *pol, + audio_stream_type_t stream, + int index); + + /* retrieve current volume index for the specified stream */ + int (*get_stream_volume_index)(const struct audio_policy *pol, + audio_stream_type_t stream, + int *index); + + /* sets the new stream volume at a level corresponding to the supplied + * index for the specified device. + * The index is within the range specified by init_stream_volume() */ + int (*set_stream_volume_index_for_device)(struct audio_policy *pol, + audio_stream_type_t stream, + int index, + audio_devices_t device); + + /* retrieve current volume index for the specified stream for the specified device */ + int (*get_stream_volume_index_for_device)(const struct audio_policy *pol, + audio_stream_type_t stream, + int *index, + audio_devices_t device); + + /* return the strategy corresponding to a given stream type */ + uint32_t (*get_strategy_for_stream)(const struct audio_policy *pol, + audio_stream_type_t stream); + + /* return the enabled output devices for the given stream type */ + audio_devices_t (*get_devices_for_stream)(const struct audio_policy *pol, + audio_stream_type_t stream); + + /* Audio effect management */ + audio_io_handle_t (*get_output_for_effect)(struct audio_policy *pol, + const struct effect_descriptor_s *desc); + + int (*register_effect)(struct audio_policy *pol, + const struct effect_descriptor_s *desc, + audio_io_handle_t output, + uint32_t strategy, + int session, + int id); + + int (*unregister_effect)(struct audio_policy *pol, int id); + + int (*set_effect_enabled)(struct audio_policy *pol, int id, bool enabled); + + bool (*is_stream_active)(const struct audio_policy *pol, + audio_stream_type_t stream, + uint32_t in_past_ms); + + bool (*is_stream_active_remotely)(const struct audio_policy *pol, + audio_stream_type_t stream, + uint32_t in_past_ms); + + bool (*is_source_active)(const struct audio_policy *pol, + audio_source_t source); + + /* dump state */ + int (*dump)(const struct audio_policy *pol, int fd); + + /* check if offload is possible for given sample rate, bitrate, duration, ... */ + bool (*is_offload_supported)(const struct audio_policy *pol, + const audio_offload_info_t *info); +}; + + +struct audio_policy_service_ops { + /* + * Audio output Control functions + */ + + /* Opens an audio output with the requested parameters. + * + * The parameter values can indicate to use the default values in case the + * audio policy manager has no specific requirements for the output being + * opened. + * + * When the function returns, the parameter values reflect the actual + * values used by the audio hardware output stream. + * + * The audio policy manager can check if the proposed parameters are + * suitable or not and act accordingly. + */ + audio_io_handle_t (*open_output)(void *service, + audio_devices_t *pDevices, + uint32_t *pSamplingRate, + audio_format_t *pFormat, + audio_channel_mask_t *pChannelMask, + uint32_t *pLatencyMs, + audio_output_flags_t flags); + + /* creates a special output that is duplicated to the two outputs passed as + * arguments. The duplication is performed by + * a special mixer thread in the AudioFlinger. + */ + audio_io_handle_t (*open_duplicate_output)(void *service, + audio_io_handle_t output1, + audio_io_handle_t output2); + + /* closes the output stream */ + int (*close_output)(void *service, audio_io_handle_t output); + + /* suspends the output. + * + * When an output is suspended, the corresponding audio hardware output + * stream is placed in standby and the AudioTracks attached to the mixer + * thread are still processed but the output mix is discarded. + */ + int (*suspend_output)(void *service, audio_io_handle_t output); + + /* restores a suspended output. */ + int (*restore_output)(void *service, audio_io_handle_t output); + + /* */ + /* Audio input Control functions */ + /* */ + + /* opens an audio input + * deprecated - new implementations should use open_input_on_module, + * and the acoustics parameter is ignored + */ + audio_io_handle_t (*open_input)(void *service, + audio_devices_t *pDevices, + uint32_t *pSamplingRate, + audio_format_t *pFormat, + audio_channel_mask_t *pChannelMask, + audio_in_acoustics_t acoustics); + + /* closes an audio input */ + int (*close_input)(void *service, audio_io_handle_t input); + + /* */ + /* misc control functions */ + /* */ + + /* set a stream volume for a particular output. + * + * For the same user setting, a given stream type can have different + * volumes for each output (destination device) it is attached to. + */ + int (*set_stream_volume)(void *service, + audio_stream_type_t stream, + float volume, + audio_io_handle_t output, + int delay_ms); + + /* invalidate a stream type, causing a reroute to an unspecified new output */ + int (*invalidate_stream)(void *service, + audio_stream_type_t stream); + + /* function enabling to send proprietary informations directly from audio + * policy manager to audio hardware interface. */ + void (*set_parameters)(void *service, + audio_io_handle_t io_handle, + const char *kv_pairs, + int delay_ms); + + /* function enabling to receive proprietary informations directly from + * audio hardware interface to audio policy manager. + * + * Returns a pointer to a heap allocated string. The caller is responsible + * for freeing the memory for it using free(). + */ + + char * (*get_parameters)(void *service, audio_io_handle_t io_handle, + const char *keys); + + /* request the playback of a tone on the specified stream. + * used for instance to replace notification sounds when playing over a + * telephony device during a phone call. + */ + int (*start_tone)(void *service, + audio_policy_tone_t tone, + audio_stream_type_t stream); + + int (*stop_tone)(void *service); + + /* set down link audio volume. */ + int (*set_voice_volume)(void *service, + float volume, + int delay_ms); + + /* move effect to the specified output */ + int (*move_effects)(void *service, + int session, + audio_io_handle_t src_output, + audio_io_handle_t dst_output); + + /* loads an audio hw module. + * + * The module name passed is the base name of the HW module library, e.g "primary" or "a2dp". + * The function returns a handle on the module that will be used to specify a particular + * module when calling open_output_on_module() or open_input_on_module() + */ + audio_module_handle_t (*load_hw_module)(void *service, + const char *name); + + /* Opens an audio output on a particular HW module. + * + * Same as open_output() but specifying a specific HW module on which the output must be opened. + */ + audio_io_handle_t (*open_output_on_module)(void *service, + audio_module_handle_t module, + audio_devices_t *pDevices, + uint32_t *pSamplingRate, + audio_format_t *pFormat, + audio_channel_mask_t *pChannelMask, + uint32_t *pLatencyMs, + audio_output_flags_t flags, + const audio_offload_info_t *offloadInfo); + + /* Opens an audio input on a particular HW module. + * + * Same as open_input() but specifying a specific HW module on which the input must be opened. + * Also removed deprecated acoustics parameter + */ + audio_io_handle_t (*open_input_on_module)(void *service, + audio_module_handle_t module, + audio_devices_t *pDevices, + uint32_t *pSamplingRate, + audio_format_t *pFormat, + audio_channel_mask_t *pChannelMask); + +}; + +/**********************************************************************/ + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct audio_policy_module { + struct hw_module_t common; +} audio_policy_module_t; + +struct audio_policy_device { + /** + * Common methods of the audio policy device. This *must* be the first member of + * audio_policy_device as users of this structure will cast a hw_device_t to + * audio_policy_device pointer in contexts where it's known the hw_device_t references an + * audio_policy_device. + */ + struct hw_device_t common; + + int (*create_audio_policy)(const struct audio_policy_device *device, + struct audio_policy_service_ops *aps_ops, + void *service, + struct audio_policy **ap); + + int (*destroy_audio_policy)(const struct audio_policy_device *device, + struct audio_policy *ap); +}; + +/** convenience API for opening and closing a supported device */ + +static inline int audio_policy_dev_open(const hw_module_t* module, + struct audio_policy_device** device) +{ + return module->methods->open(module, AUDIO_POLICY_INTERFACE, + (hw_device_t**)device); +} + +static inline int audio_policy_dev_close(struct audio_policy_device* device) +{ + return device->common.close(&device->common); +} + + +__END_DECLS + +#endif // ANDROID_AUDIO_POLICY_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/bluetooth.h b/third_party/android_hardware_libhardware/include/hardware/bluetooth.h new file mode 100644 index 00000000000000..5e8b468d64abdf --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bluetooth.h @@ -0,0 +1,595 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BLUETOOTH_H +#define ANDROID_INCLUDE_BLUETOOTH_H + +#include +#include +#include +#include + +#include + +__BEGIN_DECLS + +/** + * The Bluetooth Hardware Module ID + */ + +#define BT_HARDWARE_MODULE_ID "bluetooth" +#define BT_STACK_MODULE_ID "bluetooth" +#define BT_STACK_TEST_MODULE_ID "bluetooth_test" + + +/* Bluetooth profile interface IDs */ + +#define BT_PROFILE_HANDSFREE_ID "handsfree" +#define BT_PROFILE_HANDSFREE_CLIENT_ID "handsfree_client" +#define BT_PROFILE_ADVANCED_AUDIO_ID "a2dp" +#define BT_PROFILE_ADVANCED_AUDIO_SINK_ID "a2dp_sink" +#define BT_PROFILE_HEALTH_ID "health" +#define BT_PROFILE_SOCKETS_ID "socket" +#define BT_PROFILE_HIDHOST_ID "hidhost" +#define BT_PROFILE_HIDDEV_ID "hiddev" +#define BT_PROFILE_PAN_ID "pan" +#define BT_PROFILE_MAP_CLIENT_ID "map_client" +#define BT_PROFILE_SDP_CLIENT_ID "sdp" +#define BT_PROFILE_GATT_ID "gatt" +#define BT_PROFILE_AV_RC_ID "avrcp" +#define WIPOWER_PROFILE_ID "wipower" +#define BT_PROFILE_AV_RC_CTRL_ID "avrcp_ctrl" + +/** Bluetooth Address */ +typedef struct { + uint8_t address[6]; +} __attribute__((packed))bt_bdaddr_t; + +/** Bluetooth Device Name */ +typedef struct { + uint8_t name[249]; +} __attribute__((packed))bt_bdname_t; + +/** Bluetooth Adapter Visibility Modes*/ +typedef enum { + BT_SCAN_MODE_NONE, + BT_SCAN_MODE_CONNECTABLE, + BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE +} bt_scan_mode_t; + +/** Bluetooth Adapter State */ +typedef enum { + BT_STATE_OFF, + BT_STATE_ON +} bt_state_t; + +/** Bluetooth Error Status */ +/** We need to build on this */ + +typedef enum { + BT_STATUS_SUCCESS, + BT_STATUS_FAIL, + BT_STATUS_NOT_READY, + BT_STATUS_NOMEM, + BT_STATUS_BUSY, + BT_STATUS_DONE, /* request already completed */ + BT_STATUS_UNSUPPORTED, + BT_STATUS_PARM_INVALID, + BT_STATUS_UNHANDLED, + BT_STATUS_AUTH_FAILURE, + BT_STATUS_RMT_DEV_DOWN, + BT_STATUS_AUTH_REJECTED + +} bt_status_t; + +/** Bluetooth PinKey Code */ +typedef struct { + uint8_t pin[16]; +} __attribute__((packed))bt_pin_code_t; + +typedef struct { + uint8_t status; + uint8_t ctrl_state; /* stack reported state */ + uint64_t tx_time; /* in ms */ + uint64_t rx_time; /* in ms */ + uint64_t idle_time; /* in ms */ + uint64_t energy_used; /* a product of mA, V and ms */ +} __attribute__((packed))bt_activity_energy_info; + +/** Bluetooth Adapter Discovery state */ +typedef enum { + BT_DISCOVERY_STOPPED, + BT_DISCOVERY_STARTED +} bt_discovery_state_t; + +/** Bluetooth ACL connection state */ +typedef enum { + BT_ACL_STATE_CONNECTED, + BT_ACL_STATE_DISCONNECTED +} bt_acl_state_t; + +/** Bluetooth 128-bit UUID */ +typedef struct { + uint8_t uu[16]; +} bt_uuid_t; + +/** Bluetooth SDP service record */ +typedef struct +{ + bt_uuid_t uuid; + uint16_t channel; + char name[256]; // what's the maximum length +} bt_service_record_t; + + +/** Bluetooth Remote Version info */ +typedef struct +{ + int version; + int sub_ver; + int manufacturer; +} bt_remote_version_t; + +typedef struct +{ + uint16_t version_supported; + uint8_t local_privacy_enabled; + uint8_t max_adv_instance; + uint8_t rpa_offload_supported; + uint8_t max_irk_list_size; + uint8_t max_adv_filter_supported; + uint8_t activity_energy_info_supported; + uint16_t scan_result_storage_size; + uint16_t total_trackable_advertisers; + bool extended_scan_support; + bool debug_logging_supported; +}bt_local_le_features_t; + +/* Bluetooth Adapter and Remote Device property types */ +typedef enum { + /* Properties common to both adapter and remote device */ + /** + * Description - Bluetooth Device Name + * Access mode - Adapter name can be GET/SET. Remote device can be GET + * Data type - bt_bdname_t + */ + BT_PROPERTY_BDNAME = 0x1, + /** + * Description - Bluetooth Device Address + * Access mode - Only GET. + * Data type - bt_bdaddr_t + */ + BT_PROPERTY_BDADDR, + /** + * Description - Bluetooth Service 128-bit UUIDs + * Access mode - Only GET. + * Data type - Array of bt_uuid_t (Array size inferred from property length). + */ + BT_PROPERTY_UUIDS, + /** + * Description - Bluetooth Class of Device as found in Assigned Numbers + * Access mode - Only GET. + * Data type - uint32_t. + */ + BT_PROPERTY_CLASS_OF_DEVICE, + /** + * Description - Device Type - BREDR, BLE or DUAL Mode + * Access mode - Only GET. + * Data type - bt_device_type_t + */ + BT_PROPERTY_TYPE_OF_DEVICE, + /** + * Description - Bluetooth Service Record + * Access mode - Only GET. + * Data type - bt_service_record_t + */ + BT_PROPERTY_SERVICE_RECORD, + + /* Properties unique to adapter */ + /** + * Description - Bluetooth Adapter scan mode + * Access mode - GET and SET + * Data type - bt_scan_mode_t. + */ + BT_PROPERTY_ADAPTER_SCAN_MODE, + /** + * Description - List of bonded devices + * Access mode - Only GET. + * Data type - Array of bt_bdaddr_t of the bonded remote devices + * (Array size inferred from property length). + */ + BT_PROPERTY_ADAPTER_BONDED_DEVICES, + /** + * Description - Bluetooth Adapter Discovery timeout (in seconds) + * Access mode - GET and SET + * Data type - uint32_t + */ + BT_PROPERTY_ADAPTER_DISCOVERY_TIMEOUT, + + /* Properties unique to remote device */ + /** + * Description - User defined friendly name of the remote device + * Access mode - GET and SET + * Data type - bt_bdname_t. + */ + BT_PROPERTY_REMOTE_FRIENDLY_NAME, + /** + * Description - RSSI value of the inquired remote device + * Access mode - Only GET. + * Data type - int32_t. + */ + BT_PROPERTY_REMOTE_RSSI, + /** + * Description - Remote version info + * Access mode - SET/GET. + * Data type - bt_remote_version_t. + */ + + BT_PROPERTY_REMOTE_VERSION_INFO, + + /** + * Description - Local LE features + * Access mode - GET. + * Data type - bt_local_le_features_t. + */ + BT_PROPERTY_LOCAL_LE_FEATURES, + + BT_PROPERTY_REMOTE_DEVICE_TIMESTAMP = 0xFF, +} bt_property_type_t; + +/** Bluetooth Adapter Property data structure */ +typedef struct +{ + bt_property_type_t type; + int len; + void *val; +} bt_property_t; + + +/** Bluetooth Device Type */ +typedef enum { + BT_DEVICE_DEVTYPE_BREDR = 0x1, + BT_DEVICE_DEVTYPE_BLE, + BT_DEVICE_DEVTYPE_DUAL +} bt_device_type_t; +/** Bluetooth Bond state */ +typedef enum { + BT_BOND_STATE_NONE, + BT_BOND_STATE_BONDING, + BT_BOND_STATE_BONDED +} bt_bond_state_t; + +/** Bluetooth SSP Bonding Variant */ +typedef enum { + BT_SSP_VARIANT_PASSKEY_CONFIRMATION, + BT_SSP_VARIANT_PASSKEY_ENTRY, + BT_SSP_VARIANT_CONSENT, + BT_SSP_VARIANT_PASSKEY_NOTIFICATION +} bt_ssp_variant_t; + +#define BT_MAX_NUM_UUIDS 32 + +/** Bluetooth Interface callbacks */ + +/** Bluetooth Enable/Disable Callback. */ +typedef void (*adapter_state_changed_callback)(bt_state_t state); + +/** GET/SET Adapter Properties callback */ +/* TODO: For the GET/SET property APIs/callbacks, we may need a session + * identifier to associate the call with the callback. This would be needed + * whenever more than one simultaneous instance of the same adapter_type + * is get/set. + * + * If this is going to be handled in the Java framework, then we do not need + * to manage sessions here. + */ +typedef void (*adapter_properties_callback)(bt_status_t status, + int num_properties, + bt_property_t *properties); + +/** GET/SET Remote Device Properties callback */ +/** TODO: For remote device properties, do not see a need to get/set + * multiple properties - num_properties shall be 1 + */ +typedef void (*remote_device_properties_callback)(bt_status_t status, + bt_bdaddr_t *bd_addr, + int num_properties, + bt_property_t *properties); + +/** New device discovered callback */ +/** If EIR data is not present, then BD_NAME and RSSI shall be NULL and -1 + * respectively */ +typedef void (*device_found_callback)(int num_properties, + bt_property_t *properties); + +/** Discovery state changed callback */ +typedef void (*discovery_state_changed_callback)(bt_discovery_state_t state); + +/** Bluetooth Legacy PinKey Request callback */ +typedef void (*pin_request_callback)(bt_bdaddr_t *remote_bd_addr, + bt_bdname_t *bd_name, uint32_t cod, bool min_16_digit); + +/** Bluetooth SSP Request callback - Just Works & Numeric Comparison*/ +/** pass_key - Shall be 0 for BT_SSP_PAIRING_VARIANT_CONSENT & + * BT_SSP_PAIRING_PASSKEY_ENTRY */ +/* TODO: Passkey request callback shall not be needed for devices with display + * capability. We still need support this in the stack for completeness */ +typedef void (*ssp_request_callback)(bt_bdaddr_t *remote_bd_addr, + bt_bdname_t *bd_name, + uint32_t cod, + bt_ssp_variant_t pairing_variant, + uint32_t pass_key); + +/** Bluetooth Bond state changed callback */ +/* Invoked in response to create_bond, cancel_bond or remove_bond */ +typedef void (*bond_state_changed_callback)(bt_status_t status, + bt_bdaddr_t *remote_bd_addr, + bt_bond_state_t state); + +/** Bluetooth ACL connection state changed callback */ +typedef void (*acl_state_changed_callback)(bt_status_t status, bt_bdaddr_t *remote_bd_addr, + bt_acl_state_t state); + +typedef enum { + ASSOCIATE_JVM, + DISASSOCIATE_JVM +} bt_cb_thread_evt; + +/** Thread Associate/Disassociate JVM Callback */ +/* Callback that is invoked by the callback thread to allow upper layer to attach/detach to/from + * the JVM */ +typedef void (*callback_thread_event)(bt_cb_thread_evt evt); + +/** Bluetooth Test Mode Callback */ +/* Receive any HCI event from controller. Must be in DUT Mode for this callback to be received */ +typedef void (*dut_mode_recv_callback)(uint16_t opcode, uint8_t *buf, uint8_t len); + +/** Bluetooth HCI event Callback */ +/* Receive any HCI event from controller for raw commands */ +typedef void (*hci_event_recv_callback)(uint8_t event_code, uint8_t *buf, uint8_t len); + +/* LE Test mode callbacks +* This callback shall be invoked whenever the le_tx_test, le_rx_test or le_test_end is invoked +* The num_packets is valid only for le_test_end command */ +typedef void (*le_test_mode_callback)(bt_status_t status, uint16_t num_packets); + +/** Callback invoked when energy details are obtained */ +/* Ctrl_state-Current controller state-Active-1,scan-2,or idle-3 state as defined by HCI spec. + * If the ctrl_state value is 0, it means the API call failed + * Time values-In milliseconds as returned by the controller + * Energy used-Value as returned by the controller + * Status-Provides the status of the read_energy_info API call */ +typedef void (*energy_info_callback)(bt_activity_energy_info *energy_info); + +/** TODO: Add callbacks for Link Up/Down and other generic + * notifications/callbacks */ + +/** Bluetooth DM callback structure. */ +typedef struct { + /** set to sizeof(bt_callbacks_t) */ + size_t size; + adapter_state_changed_callback adapter_state_changed_cb; + adapter_properties_callback adapter_properties_cb; + remote_device_properties_callback remote_device_properties_cb; + device_found_callback device_found_cb; + discovery_state_changed_callback discovery_state_changed_cb; + pin_request_callback pin_request_cb; + ssp_request_callback ssp_request_cb; + bond_state_changed_callback bond_state_changed_cb; + acl_state_changed_callback acl_state_changed_cb; + callback_thread_event thread_evt_cb; + dut_mode_recv_callback dut_mode_recv_cb; + le_test_mode_callback le_test_mode_cb; + energy_info_callback energy_info_cb; + hci_event_recv_callback hci_event_recv_cb; +} bt_callbacks_t; + +typedef void (*alarm_cb)(void *data); +typedef bool (*set_wake_alarm_callout)(uint64_t delay_millis, bool should_wake, alarm_cb cb, void *data); +typedef int (*acquire_wake_lock_callout)(const char *lock_name); +typedef int (*release_wake_lock_callout)(const char *lock_name); + +/** The set of functions required by bluedroid to set wake alarms and + * grab wake locks. This struct is passed into the stack through the + * |set_os_callouts| function on |bt_interface_t|. + */ +typedef struct { + /* set to sizeof(bt_os_callouts_t) */ + size_t size; + + set_wake_alarm_callout set_wake_alarm; + acquire_wake_lock_callout acquire_wake_lock; + release_wake_lock_callout release_wake_lock; +} bt_os_callouts_t; + +/** NOTE: By default, no profiles are initialized at the time of init/enable. + * Whenever the application invokes the 'init' API of a profile, then one of + * the following shall occur: + * + * 1.) If Bluetooth is not enabled, then the Bluetooth core shall mark the + * profile as enabled. Subsequently, when the application invokes the + * Bluetooth 'enable', as part of the enable sequence the profile that were + * marked shall be enabled by calling appropriate stack APIs. The + * 'adapter_properties_cb' shall return the list of UUIDs of the + * enabled profiles. + * + * 2.) If Bluetooth is enabled, then the Bluetooth core shall invoke the stack + * profile API to initialize the profile and trigger a + * 'adapter_properties_cb' with the current list of UUIDs including the + * newly added profile's UUID. + * + * The reverse shall occur whenever the profile 'cleanup' APIs are invoked + */ + +/** Represents the standard Bluetooth DM interface. */ +typedef struct { + /** set to sizeof(bt_interface_t) */ + size_t size; + /** + * Opens the interface and provides the callback routines + * to the implemenation of this interface. + */ + int (*init)(bt_callbacks_t* callbacks ); + + /** Enable Bluetooth. */ + int (*enable)(bool guest_mode); + + /** Disable Bluetooth. */ + int (*disable)(void); + + /** Closes the interface. */ + void (*cleanup)(void); + + /** SSR cleanup. */ + void (*ssrcleanup)(void); + + /** Get all Bluetooth Adapter properties at init */ + int (*get_adapter_properties)(void); + + /** Get Bluetooth Adapter property of 'type' */ + int (*get_adapter_property)(bt_property_type_t type); + + /** Set Bluetooth Adapter property of 'type' */ + /* Based on the type, val shall be one of + * bt_bdaddr_t or bt_bdname_t or bt_scanmode_t etc + */ + int (*set_adapter_property)(const bt_property_t *property); + + /** Get all Remote Device properties */ + int (*get_remote_device_properties)(bt_bdaddr_t *remote_addr); + + /** Get Remote Device property of 'type' */ + int (*get_remote_device_property)(bt_bdaddr_t *remote_addr, + bt_property_type_t type); + + /** Set Remote Device property of 'type' */ + int (*set_remote_device_property)(bt_bdaddr_t *remote_addr, + const bt_property_t *property); + + /** Get Remote Device's service record for the given UUID */ + int (*get_remote_service_record)(bt_bdaddr_t *remote_addr, + bt_uuid_t *uuid); + + /** Start SDP to get remote services */ + int (*get_remote_services)(bt_bdaddr_t *remote_addr); + + /** Start Discovery */ + int (*start_discovery)(void); + + /** Cancel Discovery */ + int (*cancel_discovery)(void); + + /** Create Bluetooth Bonding */ + int (*create_bond)(const bt_bdaddr_t *bd_addr, int transport); + + /** Remove Bond */ + int (*remove_bond)(const bt_bdaddr_t *bd_addr); + + /** Cancel Bond */ + int (*cancel_bond)(const bt_bdaddr_t *bd_addr); + + /** + * Get the connection status for a given remote device. + * return value of 0 means the device is not connected, + * non-zero return status indicates an active connection. + */ + int (*get_connection_state)(const bt_bdaddr_t *bd_addr); + + /** BT Legacy PinKey Reply */ + /** If accept==FALSE, then pin_len and pin_code shall be 0x0 */ + int (*pin_reply)(const bt_bdaddr_t *bd_addr, uint8_t accept, + uint8_t pin_len, bt_pin_code_t *pin_code); + + /** BT SSP Reply - Just Works, Numeric Comparison and Passkey + * passkey shall be zero for BT_SSP_VARIANT_PASSKEY_COMPARISON & + * BT_SSP_VARIANT_CONSENT + * For BT_SSP_VARIANT_PASSKEY_ENTRY, if accept==FALSE, then passkey + * shall be zero */ + int (*ssp_reply)(const bt_bdaddr_t *bd_addr, bt_ssp_variant_t variant, + uint8_t accept, uint32_t passkey); + + /** Get Bluetooth profile interface */ + const void* (*get_profile_interface) (const char *profile_id); + + /** Bluetooth Test Mode APIs - Bluetooth must be enabled for these APIs */ + /* Configure DUT Mode - Use this mode to enter/exit DUT mode */ + int (*dut_mode_configure)(uint8_t enable); + + /* Send any test HCI (vendor-specific) command to the controller. Must be in DUT Mode */ + int (*dut_mode_send)(uint16_t opcode, uint8_t *buf, uint8_t len); + + /* Send any test HCI command to the controller. */ + int (*hci_cmd_send)(uint16_t opcode, uint8_t *buf, uint8_t len); + + /** BLE Test Mode APIs */ + /* opcode MUST be one of: LE_Receiver_Test, LE_Transmitter_Test, LE_Test_End */ + int (*le_test_mode)(uint16_t opcode, uint8_t *buf, uint8_t len); + + /* enable or disable bluetooth HCI snoop log */ + int (*config_hci_snoop_log)(uint8_t enable); + + /** Sets the OS call-out functions that bluedroid needs for alarms and wake locks. + * This should be called immediately after a successful |init|. + */ + int (*set_os_callouts)(bt_os_callouts_t *callouts); + + /** Read Energy info details - return value indicates BT_STATUS_SUCCESS or BT_STATUS_NOT_READY + * Success indicates that the VSC command was sent to controller + */ + int (*read_energy_info)(); + + /** + * Native support for dumpsys function + * Function is synchronous and |fd| is owned by caller. + */ + void (*dump)(int fd); + + /** + * Clear /data/misc/bt_config.conf and erase all stored connections + */ + int (*config_clear)(void); + + /** BT stack Test interface */ + const void* (*get_testapp_interface)(int test_app_profile); + + /** + * Clear (reset) the dynamic portion of the device interoperability database. + */ + void (*interop_database_clear)(void); + + /** + * Add a new device interoperability workaround for a remote device whose + * first |len| bytes of the its device address match |addr|. + * NOTE: |feature| has to match an item defined in interop_feature_t (interop.h). + */ + void (*interop_database_add)(uint16_t feature, const bt_bdaddr_t *addr, size_t len); +} bt_interface_t; + +/** TODO: Need to add APIs for Service Discovery, Service authorization and + * connection management. Also need to add APIs for configuring + * properties of remote bonded devices such as name, UUID etc. */ + +typedef struct { + struct hw_device_t common; + const bt_interface_t* (*get_bluetooth_interface)(); +} bluetooth_device_t; + +typedef bluetooth_device_t bluetooth_module_t; + + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BLUETOOTH_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_av.h b/third_party/android_hardware_libhardware/include/hardware/bt_av.h new file mode 100644 index 00000000000000..be82fbeffdbb2c --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_av.h @@ -0,0 +1,133 @@ +/* + * Copyright (C) 2013-2014, The Linux Foundation. All rights reserved. + * Not a Contribution. + * + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_AV_H +#define ANDROID_INCLUDE_BT_AV_H + +__BEGIN_DECLS + +/* Bluetooth AV connection states */ +typedef enum { + BTAV_CONNECTION_STATE_DISCONNECTED = 0, + BTAV_CONNECTION_STATE_CONNECTING, + BTAV_CONNECTION_STATE_CONNECTED, + BTAV_CONNECTION_STATE_DISCONNECTING +} btav_connection_state_t; + +/* Bluetooth AV datapath states */ +typedef enum { + BTAV_AUDIO_STATE_REMOTE_SUSPEND = 0, + BTAV_AUDIO_STATE_STOPPED, + BTAV_AUDIO_STATE_STARTED, +} btav_audio_state_t; + + +/** Callback for connection state change. + * state will have one of the values from btav_connection_state_t + */ +typedef void (* btav_connection_state_callback)(btav_connection_state_t state, + bt_bdaddr_t *bd_addr); + +/** Callback for audiopath state change. + * state will have one of the values from btav_audio_state_t + */ +typedef void (* btav_audio_state_callback)(btav_audio_state_t state, + bt_bdaddr_t *bd_addr); + +/** Callback for connection priority of device for incoming connection + * btav_connection_priority_t + */ +typedef void (* btav_connection_priority_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for audio configuration change. + * Used only for the A2DP sink interface. + * state will have one of the values from btav_audio_state_t + * sample_rate: sample rate in Hz + * channel_count: number of channels (1 for mono, 2 for stereo) + */ +typedef void (* btav_audio_config_callback)(bt_bdaddr_t *bd_addr, + uint32_t sample_rate, + uint8_t channel_count); + +/** Callback for updating apps for A2dp multicast state. + */ + +typedef void (* btav_is_multicast_enabled_callback)(int state); + +/* + * Callback for audio focus request to be used only in + * case of A2DP Sink. This is required because we are using + * AudioTrack approach for audio data rendering. + */ +typedef void (* btav_audio_focus_request_callback)(bt_bdaddr_t *bd_addr); + +/** BT-AV callback structure. */ +typedef struct { + /** set to sizeof(btav_callbacks_t) */ + size_t size; + btav_connection_state_callback connection_state_cb; + btav_audio_state_callback audio_state_cb; + btav_audio_config_callback audio_config_cb; + btav_connection_priority_callback connection_priority_cb; + btav_is_multicast_enabled_callback multicast_state_cb; + btav_audio_focus_request_callback audio_focus_request_cb; +} btav_callbacks_t; + +/** + * NOTE: + * + * 1. AVRCP 1.0 shall be supported initially. AVRCP passthrough commands + * shall be handled internally via uinput + * + * 2. A2DP data path shall be handled via a socket pipe between the AudioFlinger + * android_audio_hw library and the Bluetooth stack. + * + */ +/** Represents the standard BT-AV interface. + * Used for both the A2DP source and sink interfaces. + */ +typedef struct { + + /** set to sizeof(btav_interface_t) */ + size_t size; + /** + * Register the BtAv callbacks + */ + bt_status_t (*init)( btav_callbacks_t* callbacks , int max_a2dp_connections, + int a2dp_multicast_state); + + /** connect to headset */ + bt_status_t (*connect)( bt_bdaddr_t *bd_addr ); + + /** dis-connect from headset */ + bt_status_t (*disconnect)( bt_bdaddr_t *bd_addr ); + + /** Closes the interface. */ + void (*cleanup)( void ); + + /** Send priority of device to stack*/ + void (*allow_connection)( int is_valid , bt_bdaddr_t *bd_addr); + + /** Sends Audio Focus State. */ + void (*audio_focus_state)( int focus_state ); +} btav_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_AV_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_common_types.h b/third_party/android_hardware_libhardware/include/hardware/bt_common_types.h new file mode 100644 index 00000000000000..e30ac24e3c0a39 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_common_types.h @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/****************************************************************************** + * + * This file contains constants and definitions that can be used commonly between JNI and stack layer + * + ******************************************************************************/ +#ifndef ANDROID_INCLUDE_BT_COMMON_TYPES_H +#define ANDROID_INCLUDE_BT_COMMON_TYPES_H + +#include "bluetooth.h" + +typedef struct +{ + uint8_t client_if; + uint8_t filt_index; + uint8_t advertiser_state; + uint8_t advertiser_info_present; + uint8_t addr_type; + uint8_t tx_power; + int8_t rssi_value; + uint16_t time_stamp; + bt_bdaddr_t bd_addr; + uint8_t adv_pkt_len; + uint8_t *p_adv_pkt_data; + uint8_t scan_rsp_len; + uint8_t *p_scan_rsp_data; +} btgatt_track_adv_info_t; + +#endif /* ANDROID_INCLUDE_BT_COMMON_TYPES_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_gatt.h b/third_party/android_hardware_libhardware/include/hardware/bt_gatt.h new file mode 100644 index 00000000000000..42e14c2f15e483 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_gatt.h @@ -0,0 +1,61 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_INCLUDE_BT_GATT_H +#define ANDROID_INCLUDE_BT_GATT_H + +#include +#include "bt_gatt_client.h" +#include "bt_gatt_server.h" + +__BEGIN_DECLS + +/** BT-GATT callbacks */ +typedef struct { + /** Set to sizeof(btgatt_callbacks_t) */ + size_t size; + + /** GATT Client callbacks */ + const btgatt_client_callbacks_t* client; + + /** GATT Server callbacks */ + const btgatt_server_callbacks_t* server; +} btgatt_callbacks_t; + +/** Represents the standard Bluetooth GATT interface. */ +typedef struct { + /** Set to sizeof(btgatt_interface_t) */ + size_t size; + + /** + * Initializes the interface and provides callback routines + */ + bt_status_t (*init)( const btgatt_callbacks_t* callbacks ); + + /** Closes the interface */ + void (*cleanup)( void ); + + /** Pointer to the GATT client interface methods.*/ + const btgatt_client_interface_t* client; + + /** Pointer to the GATT server interface methods.*/ + const btgatt_server_interface_t* server; +} btgatt_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_GATT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_gatt_client.h b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_client.h new file mode 100644 index 00000000000000..e7e8e82bb97bec --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_client.h @@ -0,0 +1,455 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_INCLUDE_BT_GATT_CLIENT_H +#define ANDROID_INCLUDE_BT_GATT_CLIENT_H + +#include +#include "bt_gatt_types.h" +#include "bt_common_types.h" + +__BEGIN_DECLS + +/** + * Buffer sizes for maximum attribute length and maximum read/write + * operation buffer size. + */ +#define BTGATT_MAX_ATTR_LEN 600 + +/** Buffer type for unformatted reads/writes */ +typedef struct +{ + uint8_t value[BTGATT_MAX_ATTR_LEN]; + uint16_t len; +} btgatt_unformatted_value_t; + +/** Parameters for GATT read operations */ +typedef struct +{ + btgatt_srvc_id_t srvc_id; + btgatt_gatt_id_t char_id; + btgatt_gatt_id_t descr_id; + btgatt_unformatted_value_t value; + uint16_t value_type; + uint8_t status; +} btgatt_read_params_t; + +/** Parameters for GATT write operations */ +typedef struct +{ + btgatt_srvc_id_t srvc_id; + btgatt_gatt_id_t char_id; + btgatt_gatt_id_t descr_id; + uint8_t status; +} btgatt_write_params_t; + +/** Attribute change notification parameters */ +typedef struct +{ + uint8_t value[BTGATT_MAX_ATTR_LEN]; + bt_bdaddr_t bda; + btgatt_srvc_id_t srvc_id; + btgatt_gatt_id_t char_id; + uint16_t len; + uint8_t is_notify; +} btgatt_notify_params_t; + +typedef struct +{ + uint8_t client_if; + uint8_t action; + uint8_t filt_index; + uint16_t feat_seln; + uint16_t list_logic_type; + uint8_t filt_logic_type; + uint8_t rssi_high_thres; + uint8_t rssi_low_thres; + uint8_t dely_mode; + uint16_t found_timeout; + uint16_t lost_timeout; + uint8_t found_timeout_cnt; + uint16_t num_of_tracking_entries; +} btgatt_filt_param_setup_t; + +typedef struct +{ + bt_bdaddr_t *bda1; + bt_uuid_t *uuid1; + uint16_t u1; + uint16_t u2; + uint16_t u3; + uint16_t u4; + uint16_t u5; +} btgatt_test_params_t; + +/* BT GATT client error codes */ +typedef enum +{ + BT_GATTC_COMMAND_SUCCESS = 0, /* 0 Command succeeded */ + BT_GATTC_COMMAND_STARTED, /* 1 Command started OK. */ + BT_GATTC_COMMAND_BUSY, /* 2 Device busy with another command */ + BT_GATTC_COMMAND_STORED, /* 3 request is stored in control block */ + BT_GATTC_NO_RESOURCES, /* 4 No resources to issue command */ + BT_GATTC_MODE_UNSUPPORTED, /* 5 Request for 1 or more unsupported modes */ + BT_GATTC_ILLEGAL_VALUE, /* 6 Illegal command /parameter value */ + BT_GATTC_INCORRECT_STATE, /* 7 Device in wrong state for request */ + BT_GATTC_UNKNOWN_ADDR, /* 8 Unknown remote BD address */ + BT_GATTC_DEVICE_TIMEOUT, /* 9 Device timeout */ + BT_GATTC_INVALID_CONTROLLER_OUTPUT,/* 10 An incorrect value was received from HCI */ + BT_GATTC_SECURITY_ERROR, /* 11 Authorization or security failure or not authorized */ + BT_GATTC_DELAYED_ENCRYPTION_CHECK, /*12 Delayed encryption check */ + BT_GATTC_ERR_PROCESSING /* 12 Generic error */ +} btgattc_error_t; + +/** BT-GATT Client callback structure. */ + +/** Callback invoked in response to register_client */ +typedef void (*register_client_callback)(int status, int client_if, + bt_uuid_t *app_uuid); + +/** Callback for scan results */ +typedef void (*scan_result_callback)(bt_bdaddr_t* bda, int rssi, uint8_t* adv_data); + +/** GATT open callback invoked in response to open */ +typedef void (*connect_callback)(int conn_id, int status, int client_if, bt_bdaddr_t* bda); + +/** Callback invoked in response to close */ +typedef void (*disconnect_callback)(int conn_id, int status, + int client_if, bt_bdaddr_t* bda); + +/** + * Invoked in response to search_service when the GATT service search + * has been completed. + */ +typedef void (*search_complete_callback)(int conn_id, int status); + +/** Reports GATT services on a remote device */ +typedef void (*search_result_callback)( int conn_id, btgatt_srvc_id_t *srvc_id); + +/** GATT characteristic enumeration result callback */ +typedef void (*get_characteristic_callback)(int conn_id, int status, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + int char_prop); + +/** GATT descriptor enumeration result callback */ +typedef void (*get_descriptor_callback)(int conn_id, int status, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + btgatt_gatt_id_t *descr_id); + +/** GATT included service enumeration result callback */ +typedef void (*get_included_service_callback)(int conn_id, int status, + btgatt_srvc_id_t *srvc_id, btgatt_srvc_id_t *incl_srvc_id); + +/** Callback invoked in response to [de]register_for_notification */ +typedef void (*register_for_notification_callback)(int conn_id, + int registered, int status, btgatt_srvc_id_t *srvc_id, + btgatt_gatt_id_t *char_id); + +/** + * Remote device notification callback, invoked when a remote device sends + * a notification or indication that a client has registered for. + */ +typedef void (*notify_callback)(int conn_id, btgatt_notify_params_t *p_data); + +/** Reports result of a GATT read operation */ +typedef void (*read_characteristic_callback)(int conn_id, int status, + btgatt_read_params_t *p_data); + +/** GATT write characteristic operation callback */ +typedef void (*write_characteristic_callback)(int conn_id, int status, + btgatt_write_params_t *p_data); + +/** GATT execute prepared write callback */ +typedef void (*execute_write_callback)(int conn_id, int status); + +/** Callback invoked in response to read_descriptor */ +typedef void (*read_descriptor_callback)(int conn_id, int status, + btgatt_read_params_t *p_data); + +/** Callback invoked in response to write_descriptor */ +typedef void (*write_descriptor_callback)(int conn_id, int status, + btgatt_write_params_t *p_data); + +/** Callback triggered in response to read_remote_rssi */ +typedef void (*read_remote_rssi_callback)(int client_if, bt_bdaddr_t* bda, + int rssi, int status); + +/** + * Callback indicating the status of a listen() operation + */ +typedef void (*listen_callback)(int status, int server_if); + +/** Callback invoked when the MTU for a given connection changes */ +typedef void (*configure_mtu_callback)(int conn_id, int status, int mtu); + +/** Callback invoked when a scan filter configuration command has completed */ +typedef void (*scan_filter_cfg_callback)(int action, int client_if, int status, int filt_type, + int avbl_space); + +/** Callback invoked when scan param has been added, cleared, or deleted */ +typedef void (*scan_filter_param_callback)(int action, int client_if, int status, + int avbl_space); + +/** Callback invoked when a scan filter configuration command has completed */ +typedef void (*scan_filter_status_callback)(int enable, int client_if, int status); + +/** Callback invoked when multi-adv enable operation has completed */ +typedef void (*multi_adv_enable_callback)(int client_if, int status); + +/** Callback invoked when multi-adv param update operation has completed */ +typedef void (*multi_adv_update_callback)(int client_if, int status); + +/** Callback invoked when multi-adv instance data set operation has completed */ +typedef void (*multi_adv_data_callback)(int client_if, int status); + +/** Callback invoked when multi-adv disable operation has completed */ +typedef void (*multi_adv_disable_callback)(int client_if, int status); + +/** + * Callback notifying an application that a remote device connection is currently congested + * and cannot receive any more data. An application should avoid sending more data until + * a further callback is received indicating the congestion status has been cleared. + */ +typedef void (*congestion_callback)(int conn_id, bool congested); +/** Callback invoked when batchscan storage config operation has completed */ +typedef void (*batchscan_cfg_storage_callback)(int client_if, int status); + +/** Callback invoked when batchscan enable / disable operation has completed */ +typedef void (*batchscan_enable_disable_callback)(int action, int client_if, int status); + +/** Callback invoked when batchscan reports are obtained */ +typedef void (*batchscan_reports_callback)(int client_if, int status, int report_format, + int num_records, int data_len, uint8_t* rep_data); + +/** Callback invoked when batchscan storage threshold limit is crossed */ +typedef void (*batchscan_threshold_callback)(int client_if); + +/** Track ADV VSE callback invoked when tracked device is found or lost */ +typedef void (*track_adv_event_callback)(btgatt_track_adv_info_t *p_track_adv_info); + +/** Callback invoked when scan parameter setup has completed */ +typedef void (*scan_parameter_setup_completed_callback)(int client_if, + btgattc_error_t status); + +typedef struct { + register_client_callback register_client_cb; + scan_result_callback scan_result_cb; + connect_callback open_cb; + disconnect_callback close_cb; + search_complete_callback search_complete_cb; + search_result_callback search_result_cb; + get_characteristic_callback get_characteristic_cb; + get_descriptor_callback get_descriptor_cb; + get_included_service_callback get_included_service_cb; + register_for_notification_callback register_for_notification_cb; + notify_callback notify_cb; + read_characteristic_callback read_characteristic_cb; + write_characteristic_callback write_characteristic_cb; + read_descriptor_callback read_descriptor_cb; + write_descriptor_callback write_descriptor_cb; + execute_write_callback execute_write_cb; + read_remote_rssi_callback read_remote_rssi_cb; + listen_callback listen_cb; + configure_mtu_callback configure_mtu_cb; + scan_filter_cfg_callback scan_filter_cfg_cb; + scan_filter_param_callback scan_filter_param_cb; + scan_filter_status_callback scan_filter_status_cb; + multi_adv_enable_callback multi_adv_enable_cb; + multi_adv_update_callback multi_adv_update_cb; + multi_adv_data_callback multi_adv_data_cb; + multi_adv_disable_callback multi_adv_disable_cb; + congestion_callback congestion_cb; + batchscan_cfg_storage_callback batchscan_cfg_storage_cb; + batchscan_enable_disable_callback batchscan_enb_disable_cb; + batchscan_reports_callback batchscan_reports_cb; + batchscan_threshold_callback batchscan_threshold_cb; + track_adv_event_callback track_adv_event_cb; + scan_parameter_setup_completed_callback scan_parameter_setup_completed_cb; +} btgatt_client_callbacks_t; + +/** Represents the standard BT-GATT client interface. */ + +typedef struct { + /** Registers a GATT client application with the stack */ + bt_status_t (*register_client)( bt_uuid_t *uuid ); + + /** Unregister a client application from the stack */ + bt_status_t (*unregister_client)(int client_if ); + + /** Start or stop LE device scanning */ + bt_status_t (*scan)( bool start ); + + /** Create a connection to a remote LE or dual-mode device */ + bt_status_t (*connect)( int client_if, const bt_bdaddr_t *bd_addr, + bool is_direct, int transport ); + + /** Disconnect a remote device or cancel a pending connection */ + bt_status_t (*disconnect)( int client_if, const bt_bdaddr_t *bd_addr, + int conn_id); + + /** Start or stop advertisements to listen for incoming connections */ + bt_status_t (*listen)(int client_if, bool start); + + /** Clear the attribute cache for a given device */ + bt_status_t (*refresh)( int client_if, const bt_bdaddr_t *bd_addr ); + + /** + * Enumerate all GATT services on a connected device. + * Optionally, the results can be filtered for a given UUID. + */ + bt_status_t (*search_service)(int conn_id, bt_uuid_t *filter_uuid ); + + /** + * Enumerate included services for a given service. + * Set start_incl_srvc_id to NULL to get the first included service. + */ + bt_status_t (*get_included_service)( int conn_id, btgatt_srvc_id_t *srvc_id, + btgatt_srvc_id_t *start_incl_srvc_id); + + /** + * Enumerate characteristics for a given service. + * Set start_char_id to NULL to get the first characteristic. + */ + bt_status_t (*get_characteristic)( int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *start_char_id); + + /** + * Enumerate descriptors for a given characteristic. + * Set start_descr_id to NULL to get the first descriptor. + */ + bt_status_t (*get_descriptor)( int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + btgatt_gatt_id_t *start_descr_id); + + /** Read a characteristic on a remote device */ + bt_status_t (*read_characteristic)( int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + int auth_req ); + + /** Write a remote characteristic */ + bt_status_t (*write_characteristic)(int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + int write_type, int len, int auth_req, + char* p_value); + + /** Read the descriptor for a given characteristic */ + bt_status_t (*read_descriptor)(int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + btgatt_gatt_id_t *descr_id, int auth_req); + + /** Write a remote descriptor for a given characteristic */ + bt_status_t (*write_descriptor)( int conn_id, + btgatt_srvc_id_t *srvc_id, btgatt_gatt_id_t *char_id, + btgatt_gatt_id_t *descr_id, int write_type, int len, + int auth_req, char* p_value); + + /** Execute a prepared write operation */ + bt_status_t (*execute_write)(int conn_id, int execute); + + /** + * Register to receive notifications or indications for a given + * characteristic + */ + bt_status_t (*register_for_notification)( int client_if, + const bt_bdaddr_t *bd_addr, btgatt_srvc_id_t *srvc_id, + btgatt_gatt_id_t *char_id); + + /** Deregister a previous request for notifications/indications */ + bt_status_t (*deregister_for_notification)( int client_if, + const bt_bdaddr_t *bd_addr, btgatt_srvc_id_t *srvc_id, + btgatt_gatt_id_t *char_id); + + /** Request RSSI for a given remote device */ + bt_status_t (*read_remote_rssi)( int client_if, const bt_bdaddr_t *bd_addr); + + /** Setup scan filter params */ + bt_status_t (*scan_filter_param_setup)(btgatt_filt_param_setup_t filt_param); + + + /** Configure a scan filter condition */ + bt_status_t (*scan_filter_add_remove)(int client_if, int action, int filt_type, + int filt_index, int company_id, + int company_id_mask, const bt_uuid_t *p_uuid, + const bt_uuid_t *p_uuid_mask, const bt_bdaddr_t *bd_addr, + char addr_type, int data_len, char* p_data, int mask_len, + char* p_mask); + + /** Clear all scan filter conditions for specific filter index*/ + bt_status_t (*scan_filter_clear)(int client_if, int filt_index); + + /** Enable / disable scan filter feature*/ + bt_status_t (*scan_filter_enable)(int client_if, bool enable); + + /** Determine the type of the remote device (LE, BR/EDR, Dual-mode) */ + int (*get_device_type)( const bt_bdaddr_t *bd_addr ); + + /** Set the advertising data or scan response data */ + bt_status_t (*set_adv_data)(int client_if, bool set_scan_rsp, bool include_name, + bool include_txpower, int min_interval, int max_interval, int appearance, + uint16_t manufacturer_len, char* manufacturer_data, + uint16_t service_data_len, char* service_data, + uint16_t service_uuid_len, char* service_uuid); + + /** Configure the MTU for a given connection */ + bt_status_t (*configure_mtu)(int conn_id, int mtu); + + /** Request a connection parameter update */ + bt_status_t (*conn_parameter_update)(const bt_bdaddr_t *bd_addr, int min_interval, + int max_interval, int latency, int timeout); + + /** Sets the LE scan interval and window in units of N*0.625 msec */ + bt_status_t (*set_scan_parameters)(int client_if, int scan_interval, int scan_window); + + /* Setup the parameters as per spec, user manual specified values and enable multi ADV */ + bt_status_t (*multi_adv_enable)(int client_if, int min_interval,int max_interval,int adv_type, + int chnl_map, int tx_power, int timeout_s); + + /* Update the parameters as per spec, user manual specified values and restart multi ADV */ + bt_status_t (*multi_adv_update)(int client_if, int min_interval,int max_interval,int adv_type, + int chnl_map, int tx_power, int timeout_s); + + /* Setup the data for the specified instance */ + bt_status_t (*multi_adv_set_inst_data)(int client_if, bool set_scan_rsp, bool include_name, + bool incl_txpower, int appearance, int manufacturer_len, + char* manufacturer_data, int service_data_len, + char* service_data, int service_uuid_len, char* service_uuid); + + /* Disable the multi adv instance */ + bt_status_t (*multi_adv_disable)(int client_if); + + /* Configure the batchscan storage */ + bt_status_t (*batchscan_cfg_storage)(int client_if, int batch_scan_full_max, + int batch_scan_trunc_max, int batch_scan_notify_threshold); + + /* Enable batchscan */ + bt_status_t (*batchscan_enb_batch_scan)(int client_if, int scan_mode, + int scan_interval, int scan_window, int addr_type, int discard_rule); + + /* Disable batchscan */ + bt_status_t (*batchscan_dis_batch_scan)(int client_if); + + /* Read out batchscan reports */ + bt_status_t (*batchscan_read_reports)(int client_if, int scan_mode); + + /** Test mode interface */ + bt_status_t (*test_command)( int command, btgatt_test_params_t* params); + +} btgatt_client_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_GATT_CLIENT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_gatt_server.h b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_server.h new file mode 100644 index 00000000000000..0d6cc1e8d65183 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_server.h @@ -0,0 +1,196 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_INCLUDE_BT_GATT_SERVER_H +#define ANDROID_INCLUDE_BT_GATT_SERVER_H + +#include + +#include "bt_gatt_types.h" + +__BEGIN_DECLS + +/** GATT value type used in response to remote read requests */ +typedef struct +{ + uint8_t value[BTGATT_MAX_ATTR_LEN]; + uint16_t handle; + uint16_t offset; + uint16_t len; + uint8_t auth_req; +} btgatt_value_t; + +/** GATT remote read request response type */ +typedef union +{ + btgatt_value_t attr_value; + uint16_t handle; +} btgatt_response_t; + +/** BT-GATT Server callback structure. */ + +/** Callback invoked in response to register_server */ +typedef void (*register_server_callback)(int status, int server_if, + bt_uuid_t *app_uuid); + +/** Callback indicating that a remote device has connected or been disconnected */ +typedef void (*connection_callback)(int conn_id, int server_if, int connected, + bt_bdaddr_t *bda); + +/** Callback invoked in response to create_service */ +typedef void (*service_added_callback)(int status, int server_if, + btgatt_srvc_id_t *srvc_id, int srvc_handle); + +/** Callback indicating that an included service has been added to a service */ +typedef void (*included_service_added_callback)(int status, int server_if, + int srvc_handle, int incl_srvc_handle); + +/** Callback invoked when a characteristic has been added to a service */ +typedef void (*characteristic_added_callback)(int status, int server_if, + bt_uuid_t *uuid, int srvc_handle, int char_handle); + +/** Callback invoked when a descriptor has been added to a characteristic */ +typedef void (*descriptor_added_callback)(int status, int server_if, + bt_uuid_t *uuid, int srvc_handle, int descr_handle); + +/** Callback invoked in response to start_service */ +typedef void (*service_started_callback)(int status, int server_if, + int srvc_handle); + +/** Callback invoked in response to stop_service */ +typedef void (*service_stopped_callback)(int status, int server_if, + int srvc_handle); + +/** Callback triggered when a service has been deleted */ +typedef void (*service_deleted_callback)(int status, int server_if, + int srvc_handle); + +/** + * Callback invoked when a remote device has requested to read a characteristic + * or descriptor. The application must respond by calling send_response + */ +typedef void (*request_read_callback)(int conn_id, int trans_id, bt_bdaddr_t *bda, + int attr_handle, int offset, bool is_long); + +/** + * Callback invoked when a remote device has requested to write to a + * characteristic or descriptor. + */ +typedef void (*request_write_callback)(int conn_id, int trans_id, bt_bdaddr_t *bda, + int attr_handle, int offset, int length, + bool need_rsp, bool is_prep, uint8_t* value); + +/** Callback invoked when a previously prepared write is to be executed */ +typedef void (*request_exec_write_callback)(int conn_id, int trans_id, + bt_bdaddr_t *bda, int exec_write); + +/** + * Callback triggered in response to send_response if the remote device + * sends a confirmation. + */ +typedef void (*response_confirmation_callback)(int status, int handle); + +/** + * Callback confirming that a notification or indication has been sent + * to a remote device. + */ +typedef void (*indication_sent_callback)(int conn_id, int status); + +/** + * Callback notifying an application that a remote device connection is currently congested + * and cannot receive any more data. An application should avoid sending more data until + * a further callback is received indicating the congestion status has been cleared. + */ +typedef void (*congestion_callback)(int conn_id, bool congested); + +/** Callback invoked when the MTU for a given connection changes */ +typedef void (*mtu_changed_callback)(int conn_id, int mtu); + +typedef struct { + register_server_callback register_server_cb; + connection_callback connection_cb; + service_added_callback service_added_cb; + included_service_added_callback included_service_added_cb; + characteristic_added_callback characteristic_added_cb; + descriptor_added_callback descriptor_added_cb; + service_started_callback service_started_cb; + service_stopped_callback service_stopped_cb; + service_deleted_callback service_deleted_cb; + request_read_callback request_read_cb; + request_write_callback request_write_cb; + request_exec_write_callback request_exec_write_cb; + response_confirmation_callback response_confirmation_cb; + indication_sent_callback indication_sent_cb; + congestion_callback congestion_cb; + mtu_changed_callback mtu_changed_cb; +} btgatt_server_callbacks_t; + +/** Represents the standard BT-GATT server interface. */ +typedef struct { + /** Registers a GATT server application with the stack */ + bt_status_t (*register_server)( bt_uuid_t *uuid ); + + /** Unregister a server application from the stack */ + bt_status_t (*unregister_server)(int server_if ); + + /** Create a connection to a remote peripheral */ + bt_status_t (*connect)(int server_if, const bt_bdaddr_t *bd_addr, + bool is_direct, int transport); + + /** Disconnect an established connection or cancel a pending one */ + bt_status_t (*disconnect)(int server_if, const bt_bdaddr_t *bd_addr, + int conn_id ); + + /** Create a new service */ + bt_status_t (*add_service)( int server_if, btgatt_srvc_id_t *srvc_id, int num_handles); + + /** Assign an included service to it's parent service */ + bt_status_t (*add_included_service)( int server_if, int service_handle, int included_handle); + + /** Add a characteristic to a service */ + bt_status_t (*add_characteristic)( int server_if, + int service_handle, bt_uuid_t *uuid, + int properties, int permissions); + + /** Add a descriptor to a given service */ + bt_status_t (*add_descriptor)(int server_if, int service_handle, + bt_uuid_t *uuid, int permissions); + + /** Starts a local service */ + bt_status_t (*start_service)(int server_if, int service_handle, + int transport); + + /** Stops a local service */ + bt_status_t (*stop_service)(int server_if, int service_handle); + + /** Delete a local service */ + bt_status_t (*delete_service)(int server_if, int service_handle); + + /** Send value indication to a remote device */ + bt_status_t (*send_indication)(int server_if, int attribute_handle, + int conn_id, int len, int confirm, + char* p_value); + + /** Send a response to a read/write operation */ + bt_status_t (*send_response)(int conn_id, int trans_id, + int status, btgatt_response_t *response); + +} btgatt_server_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_GATT_CLIENT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_gatt_types.h b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_types.h new file mode 100644 index 00000000000000..e037ddcdbba7b3 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_gatt_types.h @@ -0,0 +1,56 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_INCLUDE_BT_GATT_TYPES_H +#define ANDROID_INCLUDE_BT_GATT_TYPES_H + +#include +#include + +__BEGIN_DECLS + +/** + * GATT Service types + */ +#define BTGATT_SERVICE_TYPE_PRIMARY 0 +#define BTGATT_SERVICE_TYPE_SECONDARY 1 + +/** GATT ID adding instance id tracking to the UUID */ +typedef struct +{ + bt_uuid_t uuid; + uint8_t inst_id; +} btgatt_gatt_id_t; + +/** GATT Service ID also identifies the service type (primary/secondary) */ +typedef struct +{ + btgatt_gatt_id_t id; + uint8_t is_primary; +} btgatt_srvc_id_t; + +/** Preferred physical Transport for GATT connection */ +typedef enum +{ + GATT_TRANSPORT_AUTO, + GATT_TRANSPORT_BREDR, + GATT_TRANSPORT_LE +} btgatt_transport_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_GATT_TYPES_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_hd.h b/third_party/android_hardware_libhardware/include/hardware/bt_hd.h new file mode 100644 index 00000000000000..6ba5b097d039b7 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_hd.h @@ -0,0 +1,129 @@ +/* + * Copyright (c) 2013, The Linux Foundation. All rights reserved. + * Not a Contribution + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_HD_H +#define ANDROID_INCLUDE_BT_HD_H + +#include + +__BEGIN_DECLS + +typedef enum +{ + BTHD_REPORT_TYPE_OTHER = 0, + BTHD_REPORT_TYPE_INPUT, + BTHD_REPORT_TYPE_OUTPUT, + BTHD_REPORT_TYPE_FEATURE, + BTHD_REPORT_TYPE_INTRDATA // special value for reports to be sent on INTR (INPUT is assumed) +} bthd_report_type_t; + +typedef enum +{ + BTHD_APP_STATE_NOT_REGISTERED, + BTHD_APP_STATE_REGISTERED +} bthd_application_state_t; + +typedef enum +{ + BTHD_CONN_STATE_CONNECTED, + BTHD_CONN_STATE_CONNECTING, + BTHD_CONN_STATE_DISCONNECTED, + BTHD_CONN_STATE_DISCONNECTING, + BTHD_CONN_STATE_UNKNOWN +} bthd_connection_state_t; + +typedef struct +{ + const char *name; + const char *description; + const char *provider; + uint8_t subclass; + uint8_t *desc_list; + int desc_list_len; +} bthd_app_param_t; + +typedef struct +{ + uint8_t service_type; + uint32_t token_rate; + uint32_t token_bucket_size; + uint32_t peak_bandwidth; + uint32_t access_latency; + uint32_t delay_variation; +} bthd_qos_param_t; + +typedef void (* bthd_application_state_callback)(bt_bdaddr_t *bd_addr, bthd_application_state_t state); +typedef void (* bthd_connection_state_callback)(bt_bdaddr_t *bd_addr, bthd_connection_state_t state); +typedef void (* bthd_get_report_callback)(uint8_t type, uint8_t id, uint16_t buffer_size); +typedef void (* bthd_set_report_callback)(uint8_t type, uint8_t id, uint16_t len, uint8_t *p_data); +typedef void (* bthd_set_protocol_callback)(uint8_t protocol); +typedef void (* bthd_intr_data_callback)(uint8_t report_id, uint16_t len, uint8_t *p_data); +typedef void (* bthd_vc_unplug_callback)(void); + +/** BT-HD callbacks */ +typedef struct { + size_t size; + + bthd_application_state_callback application_state_cb; + bthd_connection_state_callback connection_state_cb; + bthd_get_report_callback get_report_cb; + bthd_set_report_callback set_report_cb; + bthd_set_protocol_callback set_protocol_cb; + bthd_intr_data_callback intr_data_cb; + bthd_vc_unplug_callback vc_unplug_cb; +} bthd_callbacks_t; + +/** BT-HD interface */ +typedef struct { + + size_t size; + + /** init interface and register callbacks */ + bt_status_t (*init)(bthd_callbacks_t* callbacks); + + /** close interface */ + void (*cleanup)(void); + + /** register application */ + bt_status_t (*register_app)(bthd_app_param_t *app_param, bthd_qos_param_t *in_qos, + bthd_qos_param_t *out_qos); + + /** unregister application */ + bt_status_t (*unregister_app)(void); + + /** connects to host with virtual cable */ + bt_status_t (*connect)(void); + + /** disconnects from currently connected host */ + bt_status_t (*disconnect)(void); + + /** send report */ + bt_status_t (*send_report)(bthd_report_type_t type, uint8_t id, uint16_t len, uint8_t *p_data); + + /** notifies error for invalid SET_REPORT */ + bt_status_t (*report_error)(uint8_t error); + + /** send Virtual Cable Unplug */ + bt_status_t (*virtual_cable_unplug)(void); + +} bthd_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_HD_H */ + diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_hf.h b/third_party/android_hardware_libhardware/include/hardware/bt_hf.h new file mode 100644 index 00000000000000..dbac061308daca --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_hf.h @@ -0,0 +1,348 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_HF_H +#define ANDROID_INCLUDE_BT_HF_H + +__BEGIN_DECLS + +/* AT response code - OK/Error */ +typedef enum { + BTHF_AT_RESPONSE_ERROR = 0, + BTHF_AT_RESPONSE_OK +} bthf_at_response_t; + +typedef enum { + BTHF_CONNECTION_STATE_DISCONNECTED = 0, + BTHF_CONNECTION_STATE_CONNECTING, + BTHF_CONNECTION_STATE_CONNECTED, + BTHF_CONNECTION_STATE_SLC_CONNECTED, + BTHF_CONNECTION_STATE_DISCONNECTING +} bthf_connection_state_t; + +typedef enum { + BTHF_AUDIO_STATE_DISCONNECTED = 0, + BTHF_AUDIO_STATE_CONNECTING, + BTHF_AUDIO_STATE_CONNECTED, + BTHF_AUDIO_STATE_DISCONNECTING +} bthf_audio_state_t; + +typedef enum { + BTHF_VR_STATE_STOPPED = 0, + BTHF_VR_STATE_STARTED +} bthf_vr_state_t; + +typedef enum { + BTHF_VOLUME_TYPE_SPK = 0, + BTHF_VOLUME_TYPE_MIC +} bthf_volume_type_t; + +/* Noise Reduction and Echo Cancellation */ +typedef enum +{ + BTHF_NREC_STOP, + BTHF_NREC_START +} bthf_nrec_t; + +/* WBS codec setting */ +typedef enum +{ + BTHF_WBS_NONE, + BTHF_WBS_NO, + BTHF_WBS_YES +}bthf_wbs_config_t; + +/* BIND type*/ +typedef enum +{ + BTHF_BIND_SET, + BTHF_BIND_READ, + BTHF_BIND_TEST +}bthf_bind_type_t; + + +/* CHLD - Call held handling */ +typedef enum +{ + BTHF_CHLD_TYPE_RELEASEHELD, // Terminate all held or set UDUB("busy") to a waiting call + BTHF_CHLD_TYPE_RELEASEACTIVE_ACCEPTHELD, // Terminate all active calls and accepts a waiting/held call + BTHF_CHLD_TYPE_HOLDACTIVE_ACCEPTHELD, // Hold all active calls and accepts a waiting/held call + BTHF_CHLD_TYPE_ADDHELDTOCONF, // Add all held calls to a conference +} bthf_chld_type_t; + +/** Callback for connection state change. + * state will have one of the values from BtHfConnectionState + */ +typedef void (* bthf_connection_state_callback)(bthf_connection_state_t state, bt_bdaddr_t *bd_addr); + +/** Callback for audio connection state change. + * state will have one of the values from BtHfAudioState + */ +typedef void (* bthf_audio_state_callback)(bthf_audio_state_t state, bt_bdaddr_t *bd_addr); + +/** Callback for VR connection state change. + * state will have one of the values from BtHfVRState + */ +typedef void (* bthf_vr_cmd_callback)(bthf_vr_state_t state, bt_bdaddr_t *bd_addr); + +/** Callback for answer incoming call (ATA) + */ +typedef void (* bthf_answer_call_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for disconnect call (AT+CHUP) + */ +typedef void (* bthf_hangup_call_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for disconnect call (AT+CHUP) + * type will denote Speaker/Mic gain (BtHfVolumeControl). + */ +typedef void (* bthf_volume_cmd_callback)(bthf_volume_type_t type, int volume, bt_bdaddr_t *bd_addr); + +/** Callback for dialing an outgoing call + * If number is NULL, redial + */ +typedef void (* bthf_dial_call_cmd_callback)(char *number, bt_bdaddr_t *bd_addr); + +/** Callback for sending DTMF tones + * tone contains the dtmf character to be sent + */ +typedef void (* bthf_dtmf_cmd_callback)(char tone, bt_bdaddr_t *bd_addr); + +/** Callback for enabling/disabling noise reduction/echo cancellation + * value will be 1 to enable, 0 to disable + */ +typedef void (* bthf_nrec_cmd_callback)(bthf_nrec_t nrec, bt_bdaddr_t *bd_addr); + +/** Callback for AT+BCS and event from BAC + * WBS enable, WBS disable + */ +typedef void (* bthf_wbs_callback)(bthf_wbs_config_t wbs, bt_bdaddr_t *bd_addr); + +/** Callback for call hold handling (AT+CHLD) + * value will contain the call hold command (0, 1, 2, 3) + */ +typedef void (* bthf_chld_cmd_callback)(bthf_chld_type_t chld, bt_bdaddr_t *bd_addr); + +/** Callback for CNUM (subscriber number) + */ +typedef void (* bthf_cnum_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for indicators (CIND) + */ +typedef void (* bthf_cind_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for operator selection (COPS) + */ +typedef void (* bthf_cops_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for call list (AT+CLCC) + */ +typedef void (* bthf_clcc_cmd_callback) (bt_bdaddr_t *bd_addr); + +/** Callback for unknown AT command recd from HF + * at_string will contain the unparsed AT string + */ +typedef void (* bthf_unknown_at_cmd_callback)(char *at_string, bt_bdaddr_t *bd_addr); + +/** Callback for keypressed (HSP) event. + */ +typedef void (* bthf_key_pressed_cmd_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for HF indicators (BIND) + */ +typedef void (* bthf_bind_cmd_callback)(char* hf_ind, bthf_bind_type_t type, bt_bdaddr_t *bd_addr); + +/** Callback for HF indicator value (BIEV) + */ +typedef void (* bthf_biev_cmd_callback)(char* hf_ind_val, bt_bdaddr_t *bd_addr); + + +/** BT-HF callback structure. */ +typedef struct { + /** set to sizeof(BtHfCallbacks) */ + size_t size; + bthf_connection_state_callback connection_state_cb; + bthf_audio_state_callback audio_state_cb; + bthf_vr_cmd_callback vr_cmd_cb; + bthf_answer_call_cmd_callback answer_call_cmd_cb; + bthf_hangup_call_cmd_callback hangup_call_cmd_cb; + bthf_volume_cmd_callback volume_cmd_cb; + bthf_dial_call_cmd_callback dial_call_cmd_cb; + bthf_dtmf_cmd_callback dtmf_cmd_cb; + bthf_nrec_cmd_callback nrec_cmd_cb; + bthf_wbs_callback wbs_cb; + bthf_chld_cmd_callback chld_cmd_cb; + bthf_cnum_cmd_callback cnum_cmd_cb; + bthf_cind_cmd_callback cind_cmd_cb; + bthf_cops_cmd_callback cops_cmd_cb; + bthf_clcc_cmd_callback clcc_cmd_cb; + bthf_unknown_at_cmd_callback unknown_at_cmd_cb; + bthf_key_pressed_cmd_callback key_pressed_cmd_cb; + bthf_bind_cmd_callback bind_cmd_cb; + bthf_biev_cmd_callback biev_cmd_cb; +} bthf_callbacks_t; + +/** Network Status */ +typedef enum +{ + BTHF_NETWORK_STATE_NOT_AVAILABLE = 0, + BTHF_NETWORK_STATE_AVAILABLE +} bthf_network_state_t; + +/** Service type */ +typedef enum +{ + BTHF_SERVICE_TYPE_HOME = 0, + BTHF_SERVICE_TYPE_ROAMING +} bthf_service_type_t; + +typedef enum { + BTHF_CALL_STATE_ACTIVE = 0, + BTHF_CALL_STATE_HELD, + BTHF_CALL_STATE_DIALING, + BTHF_CALL_STATE_ALERTING, + BTHF_CALL_STATE_INCOMING, + BTHF_CALL_STATE_WAITING, + BTHF_CALL_STATE_IDLE +} bthf_call_state_t; + +typedef enum { + BTHF_CALL_DIRECTION_OUTGOING = 0, + BTHF_CALL_DIRECTION_INCOMING +} bthf_call_direction_t; + +typedef enum { + BTHF_CALL_TYPE_VOICE = 0, + BTHF_CALL_TYPE_DATA, + BTHF_CALL_TYPE_FAX +} bthf_call_mode_t; + +typedef enum { + BTHF_CALL_MPTY_TYPE_SINGLE = 0, + BTHF_CALL_MPTY_TYPE_MULTI +} bthf_call_mpty_type_t; + +typedef enum { + BTHF_HF_INDICATOR_STATE_DISABLED = 0, + BTHF_HF_INDICATOR_STATE_ENABLED +} bthf_hf_indicator_status_t; + +typedef enum { + BTHF_CALL_ADDRTYPE_UNKNOWN = 0x81, + BTHF_CALL_ADDRTYPE_INTERNATIONAL = 0x91 +} bthf_call_addrtype_t; + +typedef enum { + BTHF_VOIP_CALL_NETWORK_TYPE_MOBILE = 0, + BTHF_VOIP_CALL_NETWORK_TYPE_WIFI +} bthf_voip_call_network_type_t; + +typedef enum { + BTHF_VOIP_STATE_STOPPED = 0, + BTHF_VOIP_STATE_STARTED +} bthf_voip_state_t; + +/** Represents the standard BT-HF interface. */ +typedef struct { + + /** set to sizeof(BtHfInterface) */ + size_t size; + /** + * Register the BtHf callbacks + */ + bt_status_t (*init)( bthf_callbacks_t* callbacks, int max_hf_clients); + + /** connect to headset */ + bt_status_t (*connect)( bt_bdaddr_t *bd_addr ); + + /** dis-connect from headset */ + bt_status_t (*disconnect)( bt_bdaddr_t *bd_addr ); + + /** create an audio connection */ + bt_status_t (*connect_audio)( bt_bdaddr_t *bd_addr ); + + /** close the audio connection */ + bt_status_t (*disconnect_audio)( bt_bdaddr_t *bd_addr ); + + /** start voice recognition */ + bt_status_t (*start_voice_recognition)( bt_bdaddr_t *bd_addr ); + + /** stop voice recognition */ + bt_status_t (*stop_voice_recognition)( bt_bdaddr_t *bd_addr ); + + /** volume control */ + bt_status_t (*volume_control) (bthf_volume_type_t type, int volume, bt_bdaddr_t *bd_addr ); + + /** Combined device status change notification */ + bt_status_t (*device_status_notification)(bthf_network_state_t ntk_state, bthf_service_type_t svc_type, int signal, + int batt_chg); + + /** Response for COPS command */ + bt_status_t (*cops_response)(const char *cops, bt_bdaddr_t *bd_addr ); + + /** Response for CIND command */ + bt_status_t (*cind_response)(int svc, int num_active, int num_held, bthf_call_state_t call_setup_state, + int signal, int roam, int batt_chg, bt_bdaddr_t *bd_addr ); + + /** Pre-formatted AT response, typically in response to unknown AT cmd */ + bt_status_t (*formatted_at_response)(const char *rsp, bt_bdaddr_t *bd_addr ); + + /** ok/error response + * ERROR (0) + * OK (1) + */ + bt_status_t (*at_response) (bthf_at_response_t response_code, int error_code, bt_bdaddr_t *bd_addr ); + + /** response for CLCC command + * Can be iteratively called for each call index + * Call index of 0 will be treated as NULL termination (Completes response) + */ + bt_status_t (*clcc_response) (int index, bthf_call_direction_t dir, + bthf_call_state_t state, bthf_call_mode_t mode, + bthf_call_mpty_type_t mpty, const char *number, + bthf_call_addrtype_t type, bt_bdaddr_t *bd_addr ); + + /** notify of a call state change + * Each update notifies + * 1. Number of active/held/ringing calls + * 2. call_state: This denotes the state change that triggered this msg + * This will take one of the values from BtHfCallState + * 3. number & type: valid only for incoming & waiting call + */ + bt_status_t (*phone_state_change) (int num_active, int num_held, bthf_call_state_t call_setup_state, + const char *number, bthf_call_addrtype_t type); + + /** Closes the interface. */ + void (*cleanup)( void ); + + /** configureation for the SCO codec */ + bt_status_t (*configure_wbs)( bt_bdaddr_t *bd_addr ,bthf_wbs_config_t config ); + + /** Response for BIND READ command and activation/deactivation of HF indicator */ + bt_status_t (*bind_response) (int anum, bthf_hf_indicator_status_t status, + bt_bdaddr_t *bd_addr); + + /** Response for BIND TEST command */ + bt_status_t (*bind_string_response) (const char* result, bt_bdaddr_t *bd_addr); + + /** Sends connectivity network type used by Voip currently to stack */ + bt_status_t (*voip_network_type_wifi) (bthf_voip_state_t is_voip_started, + bthf_voip_call_network_type_t is_network_wifi); +} bthf_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_HF_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_hf_client.h b/third_party/android_hardware_libhardware/include/hardware/bt_hf_client.h new file mode 100644 index 00000000000000..0577e97d4b56d0 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_hf_client.h @@ -0,0 +1,375 @@ +/* + * Copyright (C) 2012-2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_HF_CLIENT_H +#define ANDROID_INCLUDE_BT_HF_CLIENT_H + +__BEGIN_DECLS + +typedef enum { + BTHF_CLIENT_CONNECTION_STATE_DISCONNECTED = 0, + BTHF_CLIENT_CONNECTION_STATE_CONNECTING, + BTHF_CLIENT_CONNECTION_STATE_CONNECTED, + BTHF_CLIENT_CONNECTION_STATE_SLC_CONNECTED, + BTHF_CLIENT_CONNECTION_STATE_DISCONNECTING +} bthf_client_connection_state_t; + +typedef enum { + BTHF_CLIENT_AUDIO_STATE_DISCONNECTED = 0, + BTHF_CLIENT_AUDIO_STATE_CONNECTING, + BTHF_CLIENT_AUDIO_STATE_CONNECTED, + BTHF_CLIENT_AUDIO_STATE_CONNECTED_MSBC, +} bthf_client_audio_state_t; + +typedef enum { + BTHF_CLIENT_VR_STATE_STOPPED = 0, + BTHF_CLIENT_VR_STATE_STARTED +} bthf_client_vr_state_t; + +typedef enum { + BTHF_CLIENT_VOLUME_TYPE_SPK = 0, + BTHF_CLIENT_VOLUME_TYPE_MIC +} bthf_client_volume_type_t; + +typedef enum +{ + BTHF_CLIENT_NETWORK_STATE_NOT_AVAILABLE = 0, + BTHF_CLIENT_NETWORK_STATE_AVAILABLE +} bthf_client_network_state_t; + +typedef enum +{ + BTHF_CLIENT_SERVICE_TYPE_HOME = 0, + BTHF_CLIENT_SERVICE_TYPE_ROAMING +} bthf_client_service_type_t; + +typedef enum { + BTHF_CLIENT_CALL_STATE_ACTIVE = 0, + BTHF_CLIENT_CALL_STATE_HELD, + BTHF_CLIENT_CALL_STATE_DIALING, + BTHF_CLIENT_CALL_STATE_ALERTING, + BTHF_CLIENT_CALL_STATE_INCOMING, + BTHF_CLIENT_CALL_STATE_WAITING, + BTHF_CLIENT_CALL_STATE_HELD_BY_RESP_HOLD, +} bthf_client_call_state_t; + +typedef enum { + BTHF_CLIENT_CALL_NO_CALLS_IN_PROGRESS = 0, + BTHF_CLIENT_CALL_CALLS_IN_PROGRESS +} bthf_client_call_t; + +typedef enum { + BTHF_CLIENT_CALLSETUP_NONE = 0, + BTHF_CLIENT_CALLSETUP_INCOMING, + BTHF_CLIENT_CALLSETUP_OUTGOING, + BTHF_CLIENT_CALLSETUP_ALERTING + +} bthf_client_callsetup_t; + +typedef enum { + BTHF_CLIENT_CALLHELD_NONE = 0, + BTHF_CLIENT_CALLHELD_HOLD_AND_ACTIVE, + BTHF_CLIENT_CALLHELD_HOLD, +} bthf_client_callheld_t; + +typedef enum { + BTHF_CLIENT_RESP_AND_HOLD_HELD = 0, + BTRH_CLIENT_RESP_AND_HOLD_ACCEPT, + BTRH_CLIENT_RESP_AND_HOLD_REJECT, +} bthf_client_resp_and_hold_t; + +typedef enum { + BTHF_CLIENT_CALL_DIRECTION_OUTGOING = 0, + BTHF_CLIENT_CALL_DIRECTION_INCOMING +} bthf_client_call_direction_t; + +typedef enum { + BTHF_CLIENT_CALL_MPTY_TYPE_SINGLE = 0, + BTHF_CLIENT_CALL_MPTY_TYPE_MULTI +} bthf_client_call_mpty_type_t; + +typedef enum { + BTHF_CLIENT_CMD_COMPLETE_OK = 0, + BTHF_CLIENT_CMD_COMPLETE_ERROR, + BTHF_CLIENT_CMD_COMPLETE_ERROR_NO_CARRIER, + BTHF_CLIENT_CMD_COMPLETE_ERROR_BUSY, + BTHF_CLIENT_CMD_COMPLETE_ERROR_NO_ANSWER, + BTHF_CLIENT_CMD_COMPLETE_ERROR_DELAYED, + BTHF_CLIENT_CMD_COMPLETE_ERROR_BLACKLISTED, + BTHF_CLIENT_CMD_COMPLETE_ERROR_CME +} bthf_client_cmd_complete_t; + +typedef enum { + BTHF_CLIENT_CALL_ACTION_CHLD_0 = 0, + BTHF_CLIENT_CALL_ACTION_CHLD_1, + BTHF_CLIENT_CALL_ACTION_CHLD_2, + BTHF_CLIENT_CALL_ACTION_CHLD_3, + BTHF_CLIENT_CALL_ACTION_CHLD_4, + BTHF_CLIENT_CALL_ACTION_CHLD_1x, + BTHF_CLIENT_CALL_ACTION_CHLD_2x, + BTHF_CLIENT_CALL_ACTION_ATA, + BTHF_CLIENT_CALL_ACTION_CHUP, + BTHF_CLIENT_CALL_ACTION_BTRH_0, + BTHF_CLIENT_CALL_ACTION_BTRH_1, + BTHF_CLIENT_CALL_ACTION_BTRH_2, +} bthf_client_call_action_t; + +typedef enum { + BTHF_CLIENT_SERVICE_UNKNOWN = 0, + BTHF_CLIENT_SERVICE_VOICE, + BTHF_CLIENT_SERVICE_FAX +} bthf_client_subscriber_service_type_t; + +typedef enum { + BTHF_CLIENT_IN_BAND_RINGTONE_NOT_PROVIDED = 0, + BTHF_CLIENT_IN_BAND_RINGTONE_PROVIDED, +} bthf_client_in_band_ring_state_t; + +/* Peer features masks */ +#define BTHF_CLIENT_PEER_FEAT_3WAY 0x00000001 /* Three-way calling */ +#define BTHF_CLIENT_PEER_FEAT_ECNR 0x00000002 /* Echo cancellation and/or noise reduction */ +#define BTHF_CLIENT_PEER_FEAT_VREC 0x00000004 /* Voice recognition */ +#define BTHF_CLIENT_PEER_FEAT_INBAND 0x00000008 /* In-band ring tone */ +#define BTHF_CLIENT_PEER_FEAT_VTAG 0x00000010 /* Attach a phone number to a voice tag */ +#define BTHF_CLIENT_PEER_FEAT_REJECT 0x00000020 /* Ability to reject incoming call */ +#define BTHF_CLIENT_PEER_FEAT_ECS 0x00000040 /* Enhanced Call Status */ +#define BTHF_CLIENT_PEER_FEAT_ECC 0x00000080 /* Enhanced Call Control */ +#define BTHF_CLIENT_PEER_FEAT_EXTERR 0x00000100 /* Extended error codes */ +#define BTHF_CLIENT_PEER_FEAT_CODEC 0x00000200 /* Codec Negotiation */ + +/* Peer call handling features masks */ +#define BTHF_CLIENT_CHLD_FEAT_REL 0x00000001 /* 0 Release waiting call or held calls */ +#define BTHF_CLIENT_CHLD_FEAT_REL_ACC 0x00000002 /* 1 Release active calls and accept other + (waiting or held) cal */ +#define BTHF_CLIENT_CHLD_FEAT_REL_X 0x00000004 /* 1x Release specified active call only */ +#define BTHF_CLIENT_CHLD_FEAT_HOLD_ACC 0x00000008 /* 2 Active calls on hold and accept other + (waiting or held) call */ +#define BTHF_CLIENT_CHLD_FEAT_PRIV_X 0x00000010 /* 2x Request private mode with specified + call (put the rest on hold) */ +#define BTHF_CLIENT_CHLD_FEAT_MERGE 0x00000020 /* 3 Add held call to multiparty */ +#define BTHF_CLIENT_CHLD_FEAT_MERGE_DETACH 0x00000040 /* 4 Connect two calls and leave + (disconnect from) multiparty */ + +/** Callback for connection state change. + * state will have one of the values from BtHfConnectionState + * peer/chld_features are valid only for BTHF_CLIENT_CONNECTION_STATE_SLC_CONNECTED state + */ +typedef void (* bthf_client_connection_state_callback)(bthf_client_connection_state_t state, + unsigned int peer_feat, + unsigned int chld_feat, + bt_bdaddr_t *bd_addr); + +/** Callback for audio connection state change. + * state will have one of the values from BtHfAudioState + */ +typedef void (* bthf_client_audio_state_callback)(bthf_client_audio_state_t state, + bt_bdaddr_t *bd_addr); + +/** Callback for VR connection state change. + * state will have one of the values from BtHfVRState + */ +typedef void (* bthf_client_vr_cmd_callback)(bthf_client_vr_state_t state); + +/** Callback for network state change + */ +typedef void (* bthf_client_network_state_callback) (bthf_client_network_state_t state); + +/** Callback for network roaming status change + */ +typedef void (* bthf_client_network_roaming_callback) (bthf_client_service_type_t type); + +/** Callback for signal strength indication + */ +typedef void (* bthf_client_network_signal_callback) (int signal_strength); + +/** Callback for battery level indication + */ +typedef void (* bthf_client_battery_level_callback) (int battery_level); + +/** Callback for current operator name + */ +typedef void (* bthf_client_current_operator_callback) (const char *name); + +/** Callback for call indicator + */ +typedef void (* bthf_client_call_callback) (bthf_client_call_t call); + +/** Callback for callsetup indicator + */ +typedef void (* bthf_client_callsetup_callback) (bthf_client_callsetup_t callsetup); + +/** Callback for callheld indicator + */ +typedef void (* bthf_client_callheld_callback) (bthf_client_callheld_t callheld); + +/** Callback for response and hold + */ +typedef void (* bthf_client_resp_and_hold_callback) (bthf_client_resp_and_hold_t resp_and_hold); + +/** Callback for Calling Line Identification notification + * Will be called only when there is an incoming call and number is provided. + */ +typedef void (* bthf_client_clip_callback) (const char *number); + +/** + * Callback for Call Waiting notification + */ +typedef void (* bthf_client_call_waiting_callback) (const char *number); + +/** + * Callback for listing current calls. Can be called multiple time. + * If number is unknown NULL is passed. + */ +typedef void (*bthf_client_current_calls) (int index, bthf_client_call_direction_t dir, + bthf_client_call_state_t state, + bthf_client_call_mpty_type_t mpty, + const char *number); + +/** Callback for audio volume change + */ +typedef void (*bthf_client_volume_change_callback) (bthf_client_volume_type_t type, int volume); + +/** Callback for command complete event + * cme is valid only for BTHF_CLIENT_CMD_COMPLETE_ERROR_CME type + */ +typedef void (*bthf_client_cmd_complete_callback) (bthf_client_cmd_complete_t type, int cme); + +/** Callback for subscriber information + */ +typedef void (* bthf_client_subscriber_info_callback) (const char *name, + bthf_client_subscriber_service_type_t type); + +/** Callback for in-band ring tone settings + */ +typedef void (* bthf_client_in_band_ring_tone_callback) (bthf_client_in_band_ring_state_t state); + +/** + * Callback for requested number from AG + */ +typedef void (* bthf_client_last_voice_tag_number_callback) (const char *number); + +/** + * Callback for sending ring indication to app + */ +typedef void (* bthf_client_ring_indication_callback) (void); + +/** + * Callback for sending cgmi indication to app + */ +typedef void (* bthf_client_cgmi_indication_callback) (const char *str); + +/** + * Callback for sending cgmm indication to app + */ +typedef void (* bthf_client_cgmm_indication_callback) (const char *str); + +/** BT-HF callback structure. */ +typedef struct { + /** set to sizeof(BtHfClientCallbacks) */ + size_t size; + bthf_client_connection_state_callback connection_state_cb; + bthf_client_audio_state_callback audio_state_cb; + bthf_client_vr_cmd_callback vr_cmd_cb; + bthf_client_network_state_callback network_state_cb; + bthf_client_network_roaming_callback network_roaming_cb; + bthf_client_network_signal_callback network_signal_cb; + bthf_client_battery_level_callback battery_level_cb; + bthf_client_current_operator_callback current_operator_cb; + bthf_client_call_callback call_cb; + bthf_client_callsetup_callback callsetup_cb; + bthf_client_callheld_callback callheld_cb; + bthf_client_resp_and_hold_callback resp_and_hold_cb; + bthf_client_clip_callback clip_cb; + bthf_client_call_waiting_callback call_waiting_cb; + bthf_client_current_calls current_calls_cb; + bthf_client_volume_change_callback volume_change_cb; + bthf_client_cmd_complete_callback cmd_complete_cb; + bthf_client_subscriber_info_callback subscriber_info_cb; + bthf_client_in_band_ring_tone_callback in_band_ring_tone_cb; + bthf_client_last_voice_tag_number_callback last_voice_tag_number_callback; + bthf_client_ring_indication_callback ring_indication_cb; + bthf_client_cgmi_indication_callback cgmi_cb; + bthf_client_cgmm_indication_callback cgmm_cb; +} bthf_client_callbacks_t; + +/** Represents the standard BT-HF interface. */ +typedef struct { + + /** set to sizeof(BtHfClientInterface) */ + size_t size; + /** + * Register the BtHf callbacks + */ + bt_status_t (*init)(bthf_client_callbacks_t* callbacks); + + /** connect to audio gateway */ + bt_status_t (*connect)(bt_bdaddr_t *bd_addr); + + /** disconnect from audio gateway */ + bt_status_t (*disconnect)(bt_bdaddr_t *bd_addr); + + /** create an audio connection */ + bt_status_t (*connect_audio)(bt_bdaddr_t *bd_addr); + + /** close the audio connection */ + bt_status_t (*disconnect_audio)(bt_bdaddr_t *bd_addr); + + /** start voice recognition */ + bt_status_t (*start_voice_recognition)(void); + + /** stop voice recognition */ + bt_status_t (*stop_voice_recognition)(void); + + /** volume control */ + bt_status_t (*volume_control) (bthf_client_volume_type_t type, int volume); + + /** place a call with number a number + * if number is NULL last called number is called (aka re-dial)*/ + bt_status_t (*dial) (const char *number); + + /** place a call with number specified by location (speed dial) */ + bt_status_t (*dial_memory) (int location); + + /** perform specified call related action + * idx is limited only for enhanced call control related action + */ + bt_status_t (*handle_call_action) (bthf_client_call_action_t action, int idx); + + /** query list of current calls */ + bt_status_t (*query_current_calls) (void); + + /** query name of current selected operator */ + bt_status_t (*query_current_operator_name) (void); + + /** Retrieve subscriber information */ + bt_status_t (*retrieve_subscriber_info) (void); + + /** Send DTMF code*/ + bt_status_t (*send_dtmf) (char code); + + /** Request a phone number from AG corresponding to last voice tag recorded */ + bt_status_t (*request_last_voice_tag_number) (void); + + /** Closes the interface. */ + void (*cleanup)(void); + + /** Send AT Command. */ + bt_status_t (*send_at_cmd) (int cmd, int val1, int val2, const char *arg); +} bthf_client_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_HF_CLIENT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_hh.h b/third_party/android_hardware_libhardware/include/hardware/bt_hh.h new file mode 100644 index 00000000000000..ece3c11428db54 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_hh.h @@ -0,0 +1,191 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_HH_H +#define ANDROID_INCLUDE_BT_HH_H + +#include + +__BEGIN_DECLS + +#define BTHH_MAX_DSC_LEN 884 + +/* HH connection states */ +typedef enum +{ + BTHH_CONN_STATE_CONNECTED = 0, + BTHH_CONN_STATE_CONNECTING, + BTHH_CONN_STATE_DISCONNECTED, + BTHH_CONN_STATE_DISCONNECTING, + BTHH_CONN_STATE_FAILED_MOUSE_FROM_HOST, + BTHH_CONN_STATE_FAILED_KBD_FROM_HOST, + BTHH_CONN_STATE_FAILED_TOO_MANY_DEVICES, + BTHH_CONN_STATE_FAILED_NO_BTHID_DRIVER, + BTHH_CONN_STATE_FAILED_GENERIC, + BTHH_CONN_STATE_UNKNOWN +} bthh_connection_state_t; + +typedef enum +{ + BTHH_OK = 0, + BTHH_HS_HID_NOT_READY, /* handshake error : device not ready */ + BTHH_HS_INVALID_RPT_ID, /* handshake error : invalid report ID */ + BTHH_HS_TRANS_NOT_SPT, /* handshake error : transaction not spt */ + BTHH_HS_INVALID_PARAM, /* handshake error : invalid paremter */ + BTHH_HS_ERROR, /* handshake error : unspecified HS error */ + BTHH_ERR, /* general BTA HH error */ + BTHH_ERR_SDP, /* SDP error */ + BTHH_ERR_PROTO, /* SET_Protocol error, + only used in BTA_HH_OPEN_EVT callback */ + BTHH_ERR_DB_FULL, /* device database full error, used */ + BTHH_ERR_TOD_UNSPT, /* type of device not supported */ + BTHH_ERR_NO_RES, /* out of system resources */ + BTHH_ERR_AUTH_FAILED, /* authentication fail */ + BTHH_ERR_HDL +}bthh_status_t; + +/* Protocol modes */ +typedef enum { + BTHH_REPORT_MODE = 0x00, + BTHH_BOOT_MODE = 0x01, + BTHH_UNSUPPORTED_MODE = 0xff +}bthh_protocol_mode_t; + +/* Report types */ +typedef enum { + BTHH_INPUT_REPORT = 1, + BTHH_OUTPUT_REPORT, + BTHH_FEATURE_REPORT +}bthh_report_type_t; + +typedef struct +{ + int attr_mask; + uint8_t sub_class; + uint8_t app_id; + int vendor_id; + int product_id; + int version; + uint8_t ctry_code; + int dl_len; + uint8_t dsc_list[BTHH_MAX_DSC_LEN]; +} bthh_hid_info_t; + +/** Callback for connection state change. + * state will have one of the values from bthh_connection_state_t + */ +typedef void (* bthh_connection_state_callback)(bt_bdaddr_t *bd_addr, bthh_connection_state_t state); + +/** Callback for vitual unplug api. + * the status of the vitual unplug + */ +typedef void (* bthh_virtual_unplug_callback)(bt_bdaddr_t *bd_addr, bthh_status_t hh_status); + +/** Callback for get hid info + * hid_info will contain attr_mask, sub_class, app_id, vendor_id, product_id, version, ctry_code, len + */ +typedef void (* bthh_hid_info_callback)(bt_bdaddr_t *bd_addr, bthh_hid_info_t hid_info); + +/** Callback for get protocol api. + * the protocol mode is one of the value from bthh_protocol_mode_t + */ +typedef void (* bthh_protocol_mode_callback)(bt_bdaddr_t *bd_addr, bthh_status_t hh_status, bthh_protocol_mode_t mode); + +/** Callback for get/set_idle_time api. + */ +typedef void (* bthh_idle_time_callback)(bt_bdaddr_t *bd_addr, bthh_status_t hh_status, int idle_rate); + + +/** Callback for get report api. + * if staus is ok rpt_data contains the report data + */ +typedef void (* bthh_get_report_callback)(bt_bdaddr_t *bd_addr, bthh_status_t hh_status, uint8_t* rpt_data, int rpt_size); + +/** Callback for set_report/set_protocol api and if error + * occurs for get_report/get_protocol api. + */ +typedef void (* bthh_handshake_callback)(bt_bdaddr_t *bd_addr, bthh_status_t hh_status); + + +/** BT-HH callback structure. */ +typedef struct { + /** set to sizeof(BtHfCallbacks) */ + size_t size; + bthh_connection_state_callback connection_state_cb; + bthh_hid_info_callback hid_info_cb; + bthh_protocol_mode_callback protocol_mode_cb; + bthh_idle_time_callback idle_time_cb; + bthh_get_report_callback get_report_cb; + bthh_virtual_unplug_callback virtual_unplug_cb; + bthh_handshake_callback handshake_cb; + +} bthh_callbacks_t; + + + +/** Represents the standard BT-HH interface. */ +typedef struct { + + /** set to sizeof(BtHhInterface) */ + size_t size; + + /** + * Register the BtHh callbacks + */ + bt_status_t (*init)( bthh_callbacks_t* callbacks ); + + /** connect to hid device */ + bt_status_t (*connect)( bt_bdaddr_t *bd_addr); + + /** dis-connect from hid device */ + bt_status_t (*disconnect)( bt_bdaddr_t *bd_addr ); + + /** Virtual UnPlug (VUP) the specified HID device */ + bt_status_t (*virtual_unplug)(bt_bdaddr_t *bd_addr); + + /** Set the HID device descriptor for the specified HID device. */ + bt_status_t (*set_info)(bt_bdaddr_t *bd_addr, bthh_hid_info_t hid_info ); + + /** Get the HID proto mode. */ + bt_status_t (*get_protocol) (bt_bdaddr_t *bd_addr, bthh_protocol_mode_t protocolMode); + + /** Set the HID proto mode. */ + bt_status_t (*set_protocol)(bt_bdaddr_t *bd_addr, bthh_protocol_mode_t protocolMode); + + /** Get the HID Idle Time */ + bt_status_t (*get_idle_time)(bt_bdaddr_t *bd_addr); + + /** Set the HID Idle Time */ + bt_status_t (*set_idle_time)(bt_bdaddr_t *bd_addr, uint8_t idleTime); + + /** Send a GET_REPORT to HID device. */ + bt_status_t (*get_report)(bt_bdaddr_t *bd_addr, bthh_report_type_t reportType, uint8_t reportId, int bufferSize); + + /** Send a SET_REPORT to HID device. */ + bt_status_t (*set_report)(bt_bdaddr_t *bd_addr, bthh_report_type_t reportType, char* report); + + /** Send data to HID device. */ + bt_status_t (*send_data)(bt_bdaddr_t *bd_addr, char* data); + + /** Closes the interface. */ + void (*cleanup)( void ); + +} bthh_interface_t; +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_HH_H */ + + diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_hl.h b/third_party/android_hardware_libhardware/include/hardware/bt_hl.h new file mode 100644 index 00000000000000..bd29e3abf52d70 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_hl.h @@ -0,0 +1,123 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_HL_H +#define ANDROID_INCLUDE_BT_HL_H + +__BEGIN_DECLS + +/* HL connection states */ + +typedef enum +{ + BTHL_MDEP_ROLE_SOURCE, + BTHL_MDEP_ROLE_SINK +} bthl_mdep_role_t; + +typedef enum { + BTHL_APP_REG_STATE_REG_SUCCESS, + BTHL_APP_REG_STATE_REG_FAILED, + BTHL_APP_REG_STATE_DEREG_SUCCESS, + BTHL_APP_REG_STATE_DEREG_FAILED +} bthl_app_reg_state_t; + +typedef enum +{ + BTHL_CHANNEL_TYPE_RELIABLE, + BTHL_CHANNEL_TYPE_STREAMING, + BTHL_CHANNEL_TYPE_ANY +} bthl_channel_type_t; + + +/* HL connection states */ +typedef enum { + BTHL_CONN_STATE_CONNECTING, + BTHL_CONN_STATE_CONNECTED, + BTHL_CONN_STATE_DISCONNECTING, + BTHL_CONN_STATE_DISCONNECTED, + BTHL_CONN_STATE_DESTROYED +} bthl_channel_state_t; + +typedef struct +{ + bthl_mdep_role_t mdep_role; + int data_type; + bthl_channel_type_t channel_type; + const char *mdep_description; /* MDEP description to be used in the SDP (optional); null terminated */ +} bthl_mdep_cfg_t; + +typedef struct +{ + const char *application_name; + const char *provider_name; /* provider name to be used in the SDP (optional); null terminated */ + const char *srv_name; /* service name to be used in the SDP (optional); null terminated*/ + const char *srv_desp; /* service description to be used in the SDP (optional); null terminated */ + int number_of_mdeps; + bthl_mdep_cfg_t *mdep_cfg; /* Dynamic array */ +} bthl_reg_param_t; + +/** Callback for application registration status. + * state will have one of the values from bthl_app_reg_state_t + */ +typedef void (* bthl_app_reg_state_callback)(int app_id, bthl_app_reg_state_t state); + +/** Callback for channel connection state change. + * state will have one of the values from + * bthl_connection_state_t and fd (file descriptor) + */ +typedef void (* bthl_channel_state_callback)(int app_id, bt_bdaddr_t *bd_addr, int mdep_cfg_index, int channel_id, bthl_channel_state_t state, int fd); + +/** BT-HL callback structure. */ +typedef struct { + /** set to sizeof(bthl_callbacks_t) */ + size_t size; + bthl_app_reg_state_callback app_reg_state_cb; + bthl_channel_state_callback channel_state_cb; +} bthl_callbacks_t; + + +/** Represents the standard BT-HL interface. */ +typedef struct { + + /** set to sizeof(bthl_interface_t) */ + size_t size; + + /** + * Register the Bthl callbacks + */ + bt_status_t (*init)( bthl_callbacks_t* callbacks ); + + /** Register HL application */ + bt_status_t (*register_application) ( bthl_reg_param_t *p_reg_param, int *app_id); + + /** Unregister HL application */ + bt_status_t (*unregister_application) (int app_id); + + /** connect channel */ + bt_status_t (*connect_channel)(int app_id, bt_bdaddr_t *bd_addr, int mdep_cfg_index, int *channel_id); + + /** destroy channel */ + bt_status_t (*destroy_channel)(int channel_id); + + /** Close the Bthl callback **/ + void (*cleanup)(void); + +} bthl_interface_t; +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_HL_H */ + + diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_mce.h b/third_party/android_hardware_libhardware/include/hardware/bt_mce.h new file mode 100644 index 00000000000000..5d159b336df78f --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_mce.h @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_MCE_H +#define ANDROID_INCLUDE_BT_MCE_H + +__BEGIN_DECLS + +/** MAS instance description */ +typedef struct +{ + int id; + int scn; + int msg_types; + char *p_name; +} btmce_mas_instance_t; + +/** callback for get_remote_mas_instances */ +typedef void (*btmce_remote_mas_instances_callback)(bt_status_t status, bt_bdaddr_t *bd_addr, + int num_instances, btmce_mas_instance_t *instances); + +typedef struct { + /** set to sizeof(btmce_callbacks_t) */ + size_t size; + btmce_remote_mas_instances_callback remote_mas_instances_cb; +} btmce_callbacks_t; + +typedef struct { + /** set to size of this struct */ + size_t size; + + /** register BT MCE callbacks */ + bt_status_t (*init)(btmce_callbacks_t *callbacks); + + /** search for MAS instances on remote device */ + bt_status_t (*get_remote_mas_instances)(bt_bdaddr_t *bd_addr); +} btmce_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_MCE_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_pan.h b/third_party/android_hardware_libhardware/include/hardware/bt_pan.h new file mode 100644 index 00000000000000..83e7949b216d96 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_pan.h @@ -0,0 +1,87 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_PAN_H +#define ANDROID_INCLUDE_BT_PAN_H + +__BEGIN_DECLS + +#define BTPAN_ROLE_NONE 0 +#define BTPAN_ROLE_PANNAP 1 +#define BTPAN_ROLE_PANU 2 + +typedef enum { + BTPAN_STATE_CONNECTED = 0, + BTPAN_STATE_CONNECTING = 1, + BTPAN_STATE_DISCONNECTED = 2, + BTPAN_STATE_DISCONNECTING = 3 +} btpan_connection_state_t; + +typedef enum { + BTPAN_STATE_ENABLED = 0, + BTPAN_STATE_DISABLED = 1 +} btpan_control_state_t; + +/** +* Callback for pan connection state +*/ +typedef void (*btpan_connection_state_callback)(btpan_connection_state_t state, bt_status_t error, + const bt_bdaddr_t *bd_addr, int local_role, int remote_role); +typedef void (*btpan_control_state_callback)(btpan_control_state_t state, int local_role, + bt_status_t error, const char* ifname); + +typedef struct { + size_t size; + btpan_control_state_callback control_state_cb; + btpan_connection_state_callback connection_state_cb; +} btpan_callbacks_t; +typedef struct { + /** set to size of this struct*/ + size_t size; + /** + * Initialize the pan interface and register the btpan callbacks + */ + bt_status_t (*init)(const btpan_callbacks_t* callbacks); + /* + * enable the pan service by specified role. The result state of + * enabl will be returned by btpan_control_state_callback. when pan-nap is enabled, + * the state of connecting panu device will be notified by btpan_connection_state_callback + */ + bt_status_t (*enable)(int local_role); + /* + * get current pan local role + */ + int (*get_local_role)(void); + /** + * start bluetooth pan connection to the remote device by specified pan role. The result state will be + * returned by btpan_connection_state_callback + */ + bt_status_t (*connect)(const bt_bdaddr_t *bd_addr, int local_role, int remote_role); + /** + * stop bluetooth pan connection. The result state will be returned by btpan_connection_state_callback + */ + bt_status_t (*disconnect)(const bt_bdaddr_t *bd_addr); + + /** + * Cleanup the pan interface + */ + void (*cleanup)(void); + +} btpan_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_PAN_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_rc.h b/third_party/android_hardware_libhardware/include/hardware/bt_rc.h new file mode 100644 index 00000000000000..6e1109d3817632 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_rc.h @@ -0,0 +1,527 @@ +/* + * Copyright (C) 2013-2014, The Linux Foundation. All rights reserved. + * Not a Contribution. + * + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_BT_RC_H +#define ANDROID_INCLUDE_BT_RC_H + +__BEGIN_DECLS + +/* Macros */ +#define BTRC_MAX_ATTR_STR_LEN 255 +#define BTRC_UID_SIZE 8 +#define BTRC_MAX_APP_SETTINGS 8 +#define BTRC_MAX_FOLDER_DEPTH 4 +#define BTRC_MAX_APP_ATTR_SIZE 16 +#define BTRC_MAX_ELEM_ATTR_SIZE 7 +#define BTRC_CHARSET_UTF8 0x006A + +typedef uint8_t btrc_uid_t[BTRC_UID_SIZE]; + +typedef enum { + BTRC_FEAT_NONE = 0x00, /* AVRCP 1.0 */ + BTRC_FEAT_METADATA = 0x01, /* AVRCP 1.3 */ + BTRC_FEAT_ABSOLUTE_VOLUME = 0x02, /* Supports TG role and volume sync */ + BTRC_FEAT_BROWSE = 0x04, /* AVRCP 1.4 and up, with Browsing support */ +} btrc_remote_features_t; + +typedef enum { + BTRC_PLAYSTATE_STOPPED = 0x00, /* Stopped */ + BTRC_PLAYSTATE_PLAYING = 0x01, /* Playing */ + BTRC_PLAYSTATE_PAUSED = 0x02, /* Paused */ + BTRC_PLAYSTATE_FWD_SEEK = 0x03, /* Fwd Seek*/ + BTRC_PLAYSTATE_REV_SEEK = 0x04, /* Rev Seek*/ + BTRC_PLAYSTATE_ERROR = 0xFF, /* Error */ +} btrc_play_status_t; + +typedef enum { + BTRC_EVT_PLAY_STATUS_CHANGED = 0x01, + BTRC_EVT_TRACK_CHANGE = 0x02, + BTRC_EVT_TRACK_REACHED_END = 0x03, + BTRC_EVT_TRACK_REACHED_START = 0x04, + BTRC_EVT_PLAY_POS_CHANGED = 0x05, + BTRC_EVT_APP_SETTINGS_CHANGED = 0x08, + BTRC_EVT_NOW_PLAYING_CONTENT_CHANGED = 0x09, + BTRC_EVT_AVAILABLE_PLAYERS_CHANGED = 0x0a, + BTRC_EVT_ADDRESSED_PLAYER_CHANGED = 0x0b, +} btrc_event_id_t; + +//used for Scope +typedef enum { + BTRC_EVT_MEDIA_PLAYLIST = 0, + BTRC_EVT_MEDIA_VIRTUALFILESYST = 1, + BTRC_EVT_SEARCH = 2, + BTRC_EVT_NOWPLAYING = 3, + BTRC_EVT_MAX_BROWSE = 4, +} btrc_browse_folderitem_t; + +typedef enum { + BTRC_NOTIFICATION_TYPE_INTERIM = 0, + BTRC_NOTIFICATION_TYPE_CHANGED = 1, + BTRC_NOTIFICATION_TYPE_REJECT = 2, +} btrc_notification_type_t; + +typedef enum { + BTRC_PLAYER_ATTR_EQUALIZER = 0x01, + BTRC_PLAYER_ATTR_REPEAT = 0x02, + BTRC_PLAYER_ATTR_SHUFFLE = 0x03, + BTRC_PLAYER_ATTR_SCAN = 0x04, +} btrc_player_attr_t; + +typedef enum { + BTRC_MEDIA_ATTR_TITLE = 0x01, + BTRC_MEDIA_ATTR_ARTIST = 0x02, + BTRC_MEDIA_ATTR_ALBUM = 0x03, + BTRC_MEDIA_ATTR_TRACK_NUM = 0x04, + BTRC_MEDIA_ATTR_NUM_TRACKS = 0x05, + BTRC_MEDIA_ATTR_GENRE = 0x06, + BTRC_MEDIA_ATTR_PLAYING_TIME = 0x07, +} btrc_media_attr_t; + +typedef enum { + BTRC_PLAYER_VAL_OFF_REPEAT = 0x01, + BTRC_PLAYER_VAL_SINGLE_REPEAT = 0x02, + BTRC_PLAYER_VAL_ALL_REPEAT = 0x03, + BTRC_PLAYER_VAL_GROUP_REPEAT = 0x04 +} btrc_player_repeat_val_t; + +typedef enum { + BTRC_PLAYER_VAL_OFF_SHUFFLE = 0x01, + BTRC_PLAYER_VAL_ALL_SHUFFLE = 0x02, + BTRC_PLAYER_VAL_GROUP_SHUFFLE = 0x03 +} btrc_player_shuffle_val_t; + +typedef enum { + BTRC_STS_BAD_CMD = 0x00, /* Invalid command */ + BTRC_STS_BAD_PARAM = 0x01, /* Invalid parameter */ + BTRC_STS_NOT_FOUND = 0x02, /* Specified parameter is wrong or not found */ + BTRC_STS_INTERNAL_ERR = 0x03, /* Internal Error */ + BTRC_STS_NO_ERROR = 0x04 /* Operation Success */ +} btrc_status_t; + +typedef enum { + BTRC_TYPE_MEDIA_PLAYER = 0x01, + BTRC_TYPE_FOLDER = 0x02, + BTRC_TYPE_MEDIA_ELEMENT = 0x03 +} btrc_folder_list_item_type_t; + +typedef struct { + uint8_t num_attr; + uint8_t attr_ids[BTRC_MAX_APP_SETTINGS]; + uint8_t attr_values[BTRC_MAX_APP_SETTINGS]; +} btrc_player_settings_t; + +typedef struct { + uint32_t start_item; + uint32_t end_item; + uint32_t size; + uint32_t attrs[BTRC_MAX_ELEM_ATTR_SIZE]; + uint8_t attr_count; +}btrc_getfolderitem_t; + +typedef union +{ + btrc_play_status_t play_status; + btrc_uid_t track; /* queue position in NowPlaying */ + uint32_t song_pos; + btrc_player_settings_t player_setting; + uint16_t player_id; +} btrc_register_notification_t; + +typedef struct { + uint8_t id; /* can be attr_id or value_id */ + uint8_t text[BTRC_MAX_ATTR_STR_LEN]; +} btrc_player_setting_text_t; + +typedef struct { + uint32_t attr_id; + uint8_t text[BTRC_MAX_ATTR_STR_LEN]; +} btrc_element_attr_val_t; + +/** Callback for the controller's supported feautres */ +typedef void (* btrc_remote_features_callback)(bt_bdaddr_t *bd_addr, + btrc_remote_features_t features); +#define BTRC_FEATURE_MASK_SIZE 16 + +typedef uint8_t btrc_feature_mask_t[BTRC_FEATURE_MASK_SIZE]; + +typedef struct { + uint16_t charset_id; + uint16_t str_len; + uint8_t *p_str; +} btrc_player_full_name_t; + +typedef struct +{ + uint32_t sub_type; + uint16_t player_id; + uint8_t major_type; + uint8_t play_status; + btrc_feature_mask_t features; /* Supported feature bit mask*/ + btrc_player_full_name_t name; /* The player name, name length and character set id.*/ +} btrc_folder_list_item_player_t; + +typedef struct +{ + uint64_t uid; + uint8_t type; + uint8_t playable; + btrc_player_full_name_t name; +} btrc_folder_list_item_folder_t; + +typedef struct +{ + uint32_t attr_id; + btrc_player_full_name_t name; +} btrc_attr_entry_t; + +typedef struct +{ + uint64_t uid; + uint8_t type; + uint8_t attr_count; + btrc_player_full_name_t name; + btrc_attr_entry_t* p_attr_list; +} btrc_folder_list_item_media_t; + +typedef struct { + uint16_t str_len; + uint8_t *p_str; +} btrc_name_t; + +/* SetBrowsedPlayer */ +typedef struct +{ + uint32_t num_items; + uint16_t uid_counter; + uint16_t charset_id; + uint8_t status; + uint8_t folder_depth; + btrc_name_t *p_folders; +} btrc_set_browsed_player_rsp_t; + +typedef struct +{ + uint8_t item_type; + union + { + btrc_folder_list_item_player_t player; + btrc_folder_list_item_folder_t folder; + btrc_folder_list_item_media_t media; + } u; +} btrc_folder_list_item_t; + +/* GetFolderItems */ +typedef struct +{ + uint16_t uid_counter; + uint16_t item_count; + uint8_t status; + btrc_folder_list_item_t *p_item_list; +} btrc_folder_list_entries_t; + +/** Callback for play status request */ +typedef void (* btrc_get_play_status_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for list player application attributes (Shuffle, Repeat,...) */ +typedef void (* btrc_list_player_app_attr_callback)(bt_bdaddr_t *bd_addr); + +/** Callback for list player application attributes (Shuffle, Repeat,...) */ +typedef void (* btrc_list_player_app_values_callback)(btrc_player_attr_t attr_id, + bt_bdaddr_t *bd_addr); + +/** Callback for getting the current player application settings value +** num_attr: specifies the number of attribute ids contained in p_attrs +*/ +typedef void (* btrc_get_player_app_value_callback) (uint8_t num_attr, btrc_player_attr_t *p_attrs, + bt_bdaddr_t *bd_addr); + +/** Callback for getting the player application settings attributes' text +** num_attr: specifies the number of attribute ids contained in p_attrs +*/ +typedef void (* btrc_get_player_app_attrs_text_callback) (uint8_t num_attr, + btrc_player_attr_t *p_attrs, bt_bdaddr_t *bd_addr); + +/** Callback for getting the player application settings values' text +** num_attr: specifies the number of value ids contained in p_vals +*/ +typedef void (* btrc_get_player_app_values_text_callback) (uint8_t attr_id, + uint8_t num_val, uint8_t *p_vals, bt_bdaddr_t *bd_addr); + +/** Callback for setting the player application settings values */ +typedef void (* btrc_set_player_app_value_callback) (btrc_player_settings_t *p_vals, + bt_bdaddr_t *bd_addr); + +/** Callback to fetch the get element attributes of the current song +** num_attr: specifies the number of attributes requested in p_attrs +*/ +typedef void (* btrc_get_element_attr_callback) (uint8_t num_attr, btrc_media_attr_t *p_attrs, + bt_bdaddr_t *bd_addr); + +/** Callback for register notification (Play state change/track change/...) +** param: Is only valid if event_id is BTRC_EVT_PLAY_POS_CHANGED +*/ +typedef void (* btrc_register_notification_callback) (btrc_event_id_t event_id, uint32_t param, + bt_bdaddr_t *bd_addr); + +/* AVRCP 1.4 Enhancements */ +/** Callback for volume change on CT +** volume: Current volume setting on the CT (0-127) +*/ +typedef void (* btrc_volume_change_callback) (uint8_t volume, uint8_t ctype, bt_bdaddr_t *bd_addr); + +/** Callback for passthrough commands */ +typedef void (* btrc_passthrough_cmd_callback) (int id, int key_state, bt_bdaddr_t *bd_addr); + +/** BT-RC Target callback structure. */ + +typedef void (* btrc_get_folder_items_callback) (btrc_browse_folderitem_t id, + btrc_getfolderitem_t *param, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_set_addressed_player_callback) (uint32_t player_id, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_set_browsed_player_callback) (uint32_t player_id, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_change_path_callback) (uint8_t direction, uint64_t uid, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_play_item_callback) (uint8_t scope, uint64_t uid, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_get_item_attr_callback) (uint8_t scope, uint64_t uid, + uint8_t num_attr, btrc_media_attr_t *p_attrs, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_connection_state_callback) (bool state, bt_bdaddr_t *bd_addr); + +typedef struct { + /** set to sizeof(BtRcCallbacks) */ + size_t size; + btrc_remote_features_callback remote_features_cb; + btrc_get_play_status_callback get_play_status_cb; + btrc_list_player_app_attr_callback list_player_app_attr_cb; + btrc_list_player_app_values_callback list_player_app_values_cb; + btrc_get_player_app_value_callback get_player_app_value_cb; + btrc_get_player_app_attrs_text_callback get_player_app_attrs_text_cb; + btrc_get_player_app_values_text_callback get_player_app_values_text_cb; + btrc_set_player_app_value_callback set_player_app_value_cb; + btrc_get_element_attr_callback get_element_attr_cb; + btrc_register_notification_callback register_notification_cb; + btrc_volume_change_callback volume_change_cb; + btrc_passthrough_cmd_callback passthrough_cmd_cb; + btrc_get_folder_items_callback get_folderitems_cb; + btrc_set_addressed_player_callback set_addrplayer_cb; + btrc_set_browsed_player_callback set_browsed_player_cb; + btrc_change_path_callback change_path_cb; + btrc_play_item_callback play_item_cb; + btrc_get_item_attr_callback get_item_attr_cb; + btrc_connection_state_callback connection_state_cb; +} btrc_callbacks_t; + +/** Represents the standard BT-RC AVRCP Target interface. */ +typedef struct { + + /** set to sizeof(BtRcInterface) */ + size_t size; + /** + * Register the BtRc callbacks + */ + bt_status_t (*init)( btrc_callbacks_t* callbacks , int max_avrcp_connections); + + /** Respose to GetPlayStatus request. Contains the current + ** 1. Play status + ** 2. Song duration/length + ** 3. Song position + */ + bt_status_t (*get_play_status_rsp)( btrc_play_status_t play_status, uint32_t song_len, + uint32_t song_pos, bt_bdaddr_t *bd_addr); + + /** Lists the support player application attributes (Shuffle/Repeat/...) + ** num_attr: Specifies the number of attributes contained in the pointer p_attrs + */ + bt_status_t (*list_player_app_attr_rsp)( uint8_t num_attr, btrc_player_attr_t *p_attrs, + bt_bdaddr_t *bd_addr); + + /** Lists the support player application attributes (Shuffle Off/On/Group) + ** num_val: Specifies the number of values contained in the pointer p_vals + */ + bt_status_t (*list_player_app_value_rsp)( uint8_t num_val, uint8_t *p_vals, + bt_bdaddr_t *bd_addr); + + /** Returns the current application attribute values for each of the specified attr_id */ + bt_status_t (*get_player_app_value_rsp)( btrc_player_settings_t *p_vals, + bt_bdaddr_t *bd_addr); + + /** Returns the application attributes text ("Shuffle"/"Repeat"/...) + ** num_attr: Specifies the number of attributes' text contained in the pointer p_attrs + */ + bt_status_t (*get_player_app_attr_text_rsp)( int num_attr, btrc_player_setting_text_t *p_attrs, + bt_bdaddr_t *bd_addr); + + /** Returns the application attributes text ("Shuffle"/"Repeat"/...) + ** num_attr: Specifies the number of attribute values' text contained in the pointer p_vals + */ + bt_status_t (*get_player_app_value_text_rsp)( int num_val, btrc_player_setting_text_t *p_vals, + bt_bdaddr_t *bd_addr); + + /** Returns the current songs' element attributes text ("Title"/"Album"/"Artist") + ** num_attr: Specifies the number of attributes' text contained in the pointer p_attrs + */ + bt_status_t (*get_element_attr_rsp)( uint8_t num_attr, btrc_element_attr_val_t *p_attrs, + bt_bdaddr_t *bd_addr); + + /** Response to set player attribute request ("Shuffle"/"Repeat") + ** rsp_status: Status of setting the player attributes for the current media player + */ + bt_status_t (*set_player_app_value_rsp)(btrc_status_t rsp_status, bt_bdaddr_t *bd_addr); + + /* Response to the register notification request (Play state change/track change/...). + ** event_id: Refers to the event_id this notification change corresponds too + ** type: Response type - interim/changed + ** p_params: Based on the event_id, this parameter should be populated + */ + bt_status_t (*register_notification_rsp)(btrc_event_id_t event_id, + btrc_notification_type_t type, + btrc_register_notification_t *p_param, + bt_bdaddr_t *bd_addr); + + /* AVRCP 1.4 enhancements */ + + /**Send current volume setting to remote side. Support limited to SetAbsoluteVolume + ** This can be enhanced to support Relative Volume (AVRCP 1.0). + ** With RelateVolume, we will send VOLUME_UP/VOLUME_DOWN opposed to absolute volume level + ** volume: Should be in the range 0-127. bit7 is reseved and cannot be set + */ + bt_status_t (*set_volume)(uint8_t volume, bt_bdaddr_t *bd_addr); + bt_status_t (*get_folder_items_rsp) (btrc_folder_list_entries_t *p_param, bt_bdaddr_t *bd_addr); + + bt_status_t (*set_addressed_player_rsp) (btrc_status_t status_code, bt_bdaddr_t *bd_addr); + bt_status_t (*set_browsed_player_rsp) (btrc_set_browsed_player_rsp_t *p_param, + bt_bdaddr_t *bd_addr); + bt_status_t (*change_path_rsp) (uint8_t status_code, uint32_t item_count, + bt_bdaddr_t *bd_addr); + bt_status_t (*play_item_rsp) (uint8_t status_code, bt_bdaddr_t *bd_addr); + bt_status_t (*get_item_attr_rsp)( uint8_t num_attr, btrc_element_attr_val_t *p_attrs, + bt_bdaddr_t *bd_addr); + bt_status_t (*is_device_active_in_handoff) (bt_bdaddr_t *bd_addr); + + /** Closes the interface. */ + void (*cleanup)( void ); +} btrc_interface_t; + + +typedef void (* btrc_passthrough_rsp_callback) (int id, int key_state); + +typedef void (* btrc_connection_state_callback) (bool state, bt_bdaddr_t *bd_addr); + +typedef void (* btrc_ctrl_getrcfeatures_callback) (bt_bdaddr_t *bd_addr, int features); + +typedef void (* btrc_ctrl_getcapability_rsp_callback) (bt_bdaddr_t *bd_addr, int cap_id, + uint32_t* supported_values, int num_supported, uint8_t rsp_type); + +typedef void (* btrc_ctrl_listplayerappsettingattrib_rsp_callback) (bt_bdaddr_t *bd_addr, + uint8_t* supported_attribs, int num_attrib, uint8_t rsp_type); + +typedef void (* btrc_ctrl_listplayerappsettingvalue_rsp_callback) (bt_bdaddr_t *bd_addr, + uint8_t* supported_val, uint8_t num_supported, uint8_t rsp_type); + +typedef void (* btrc_ctrl_currentplayerappsetting_rsp_callback) (bt_bdaddr_t *bd_addr,uint8_t* supported_ids, + uint8_t* supported_val, uint8_t num_attrib, uint8_t rsp_type); + +typedef void (* btrc_ctrl_setplayerapplicationsetting_rsp_callback) (bt_bdaddr_t *bd_addr,uint8_t rsp_type); + +typedef void (* btrc_ctrl_notification_rsp_callback) (bt_bdaddr_t *bd_addr, uint8_t rsp_type, + int rsp_len, uint8_t* notification_rsp); + +typedef void (* btrc_ctrl_getelementattrib_rsp_callback) (bt_bdaddr_t *bd_addr, uint8_t num_attributes, + int rsp_len, uint8_t* attrib_rsp, uint8_t rsp_type); + +typedef void (* btrc_ctrl_getplaystatus_rsp_callback) (bt_bdaddr_t *bd_addr, int param_len, uint8_t* play_status_rsp + ,uint8_t rsp_type); + +typedef void (* btrc_ctrl_setabsvol_cmd_callback) (bt_bdaddr_t *bd_addr, uint8_t abs_vol); + +typedef void (* btrc_ctrl_registernotification_abs_vol_callback) (bt_bdaddr_t *bd_addr); +/** BT-RC Controller callback structure. */ +typedef struct { + /** set to sizeof(BtRcCallbacks) */ + size_t size; + btrc_passthrough_rsp_callback passthrough_rsp_cb; + btrc_connection_state_callback connection_state_cb; + btrc_ctrl_getrcfeatures_callback getrcfeatures_cb; + btrc_ctrl_getcapability_rsp_callback getcap_rsp_cb; + btrc_ctrl_listplayerappsettingattrib_rsp_callback listplayerappsettingattrib_rsp_cb; + btrc_ctrl_listplayerappsettingvalue_rsp_callback listplayerappsettingvalue_rsp_cb; + btrc_ctrl_currentplayerappsetting_rsp_callback currentplayerappsetting_rsp_cb; + btrc_ctrl_setplayerapplicationsetting_rsp_callback setplayerappsetting_rsp_cb; + btrc_ctrl_notification_rsp_callback notification_rsp_cb; + btrc_ctrl_getelementattrib_rsp_callback getelementattrib_rsp_cb; + btrc_ctrl_getplaystatus_rsp_callback getplaystatus_rsp_cb; + btrc_ctrl_setabsvol_cmd_callback setabsvol_cmd_cb; + btrc_ctrl_registernotification_abs_vol_callback registernotification_absvol_cb; +} btrc_ctrl_callbacks_t; + +/** Represents the standard BT-RC AVRCP Controller interface. */ +typedef struct { + + /** set to sizeof(BtRcInterface) */ + size_t size; + /** + * Register the BtRc callbacks + */ + bt_status_t (*init)( btrc_ctrl_callbacks_t* callbacks ); + + /** send pass through command to target */ + bt_status_t (*send_pass_through_cmd) ( bt_bdaddr_t *bd_addr, uint8_t key_code, + uint8_t key_state ); + + /** send get_cap command to target */ + bt_status_t (*getcapabilities_cmd) (uint8_t cap_id); + + /** send command to get supported player application settings to target */ + bt_status_t (*list_player_app_setting_attrib_cmd) (void); + + /** send command to get supported values of player application settings for a + * particular attribute to target */ + bt_status_t (*list_player_app_setting_value_cmd) (uint8_t attrib_id); + + /** send command to get current player attributes to target */ + bt_status_t (*get_player_app_setting_cmd) (uint8_t num_attrib, uint8_t* attrib_ids); + + /** send command to set player applicaiton setting attributes to target */ + bt_status_t (*set_player_app_setting_cmd) (uint8_t num_attrib, uint8_t* attrib_ids, uint8_t* attrib_vals); + + /** send command to register for supported notificaiton events to target */ + bt_status_t (*register_notification_cmd) (uint8_t event_id, uint32_t event_value); + + /** send command to get element attribute to target */ + bt_status_t (*get_element_attribute_cmd) (uint8_t num_attribute, uint32_t attribute_id); + + /** send command to get play status to target */ + bt_status_t (*get_play_status_cmd) (void); + + /** send rsp to set_abs_vol received from target */ + bt_status_t (*send_abs_vol_rsp) (uint8_t abs_vol); + + /** send notificaiton rsp for abs vol to target */ + bt_status_t (*send_register_abs_vol_rsp) (uint8_t rsp_type, uint8_t abs_vol); + + /** Closes the interface. */ + void (*cleanup)( void ); +} btrc_ctrl_interface_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_BT_RC_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_sdp.h b/third_party/android_hardware_libhardware/include/hardware/bt_sdp.h new file mode 100644 index 00000000000000..8f39bc5bdc467c --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_sdp.h @@ -0,0 +1,150 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +#include "bluetooth.h" + +#define SDP_OPP_SUPPORTED_FORMATS_MAX_LENGTH 15 + +__BEGIN_DECLS + +/** + * These events are handled by the state machine + */ +typedef enum { + SDP_TYPE_RAW, // Used to carry raw SDP search data for unknown UUIDs + SDP_TYPE_MAP_MAS, // Message Access Profile - Server + SDP_TYPE_MAP_MNS, // Message Access Profile - Client (Notification Server) + SDP_TYPE_PBAP_PSE, // Phone Book Profile - Server + SDP_TYPE_PBAP_PCE, // Phone Book Profile - Client + SDP_TYPE_OPP_SERVER, // Object Push Profile + SDP_TYPE_SAP_SERVER // SIM Access Profile +} bluetooth_sdp_types; + +typedef struct _bluetooth_sdp_hdr { + bluetooth_sdp_types type; + bt_uuid_t uuid; + uint32_t service_name_length; + char *service_name; + int32_t rfcomm_channel_number; + int32_t l2cap_psm; + int32_t profile_version; +} bluetooth_sdp_hdr; + +/** + * Some signals need additional pointers, hence we introduce a + * generic way to handle these pointers. + */ +typedef struct _bluetooth_sdp_hdr_overlay { + bluetooth_sdp_types type; + bt_uuid_t uuid; + uint32_t service_name_length; + char *service_name; + int32_t rfcomm_channel_number; + int32_t l2cap_psm; + int32_t profile_version; + + // User pointers, only used for some signals - see bluetooth_sdp_ops_record + int user1_ptr_len; + uint8_t *user1_ptr; + int user2_ptr_len; + uint8_t *user2_ptr; +} bluetooth_sdp_hdr_overlay; + +typedef struct _bluetooth_sdp_mas_record { + bluetooth_sdp_hdr_overlay hdr; + uint32_t mas_instance_id; + uint32_t supported_features; + uint32_t supported_message_types; +} bluetooth_sdp_mas_record; + +typedef struct _bluetooth_sdp_mns_record { + bluetooth_sdp_hdr_overlay hdr; + uint32_t supported_features; +} bluetooth_sdp_mns_record; + +typedef struct _bluetooth_sdp_pse_record { + bluetooth_sdp_hdr_overlay hdr; + uint32_t supported_features; + uint32_t supported_repositories; +} bluetooth_sdp_pse_record; + +typedef struct _bluetooth_sdp_pce_record { + bluetooth_sdp_hdr_overlay hdr; +} bluetooth_sdp_pce_record; + +typedef struct _bluetooth_sdp_ops_record { + bluetooth_sdp_hdr_overlay hdr; + int supported_formats_list_len; + uint8_t supported_formats_list[SDP_OPP_SUPPORTED_FORMATS_MAX_LENGTH]; +} bluetooth_sdp_ops_record; + +typedef struct _bluetooth_sdp_sap_record { + bluetooth_sdp_hdr_overlay hdr; +} bluetooth_sdp_sap_record; + +typedef union { + bluetooth_sdp_hdr_overlay hdr; + bluetooth_sdp_mas_record mas; + bluetooth_sdp_mns_record mns; + bluetooth_sdp_pse_record pse; + bluetooth_sdp_pce_record pce; + bluetooth_sdp_ops_record ops; + bluetooth_sdp_sap_record sap; +} bluetooth_sdp_record; + + +/** Callback for SDP search */ +typedef void (*btsdp_search_callback)(bt_status_t status, bt_bdaddr_t *bd_addr, uint8_t* uuid, int num_records, bluetooth_sdp_record *records); + +typedef struct { + /** Set to sizeof(btsdp_callbacks_t) */ + size_t size; + btsdp_search_callback sdp_search_cb; +} btsdp_callbacks_t; + +typedef struct { + /** Set to size of this struct */ + size_t size; + + /** Register BT SDP search callbacks */ + bt_status_t (*init)(btsdp_callbacks_t *callbacks); + + /** Unregister BT SDP */ + bt_status_t (*deinit)(); + + /** Search for SDP records with specific uuid on remote device */ + bt_status_t (*sdp_search)(bt_bdaddr_t *bd_addr, const uint8_t* uuid); + + /** + * Use listen in the socket interface to create rfcomm and/or l2cap PSM channels, + * (without UUID and service_name and set the BTSOCK_FLAG_NO_SDP flag in flags). + * Then use createSdpRecord to create the SDP record associated with the rfcomm/l2cap channels. + * + * Returns a handle to the SDP record, which can be parsed to remove_sdp_record. + * + * record (in) The SDP record to create + * record_handle (out)The corresponding record handle will be written to this pointer. + */ + bt_status_t (*create_sdp_record)(bluetooth_sdp_record *record, int* record_handle); + + /** Remove a SDP record created by createSdpRecord */ + bt_status_t (*remove_sdp_record)(int sdp_handle); +} btsdp_interface_t; + +__END_DECLS + diff --git a/third_party/android_hardware_libhardware/include/hardware/bt_sock.h b/third_party/android_hardware_libhardware/include/hardware/bt_sock.h new file mode 100644 index 00000000000000..9dd83bb1c9f9f2 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/bt_sock.h @@ -0,0 +1,91 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +__BEGIN_DECLS + +#define BTSOCK_FLAG_ENCRYPT 1 +#define BTSOCK_FLAG_AUTH (1 << 1) +#define BTSOCK_FLAG_NO_SDP (1 << 2) +#define BTSOCK_FLAG_AUTH_MITM (1 << 3) +#define BTSOCK_FLAG_AUTH_16_DIGIT (1 << 4) + +typedef enum { + BTSOCK_RFCOMM = 1, + BTSOCK_SCO = 2, + BTSOCK_L2CAP = 3 +} btsock_type_t; + +typedef enum { + BTSOCK_OPT_GET_MODEM_BITS = 1, + BTSOCK_OPT_SET_MODEM_BITS = 2, + BTSOCK_OPT_CLR_MODEM_BITS = 3, +} btsock_option_type_t; + +/** Represents the standard BT SOCKET interface. */ +typedef struct { + short size; + bt_bdaddr_t bd_addr; + int channel; + int status; + + // The writer must make writes using a buffer of this maximum size + // to avoid loosing data. (L2CAP only) + unsigned short max_tx_packet_size; + + // The reader must read using a buffer of at least this size to avoid + // loosing data. (L2CAP only) + unsigned short max_rx_packet_size; +} __attribute__((packed)) sock_connect_signal_t; + +typedef struct { + /** set to size of this struct*/ + size_t size; + + /** + * Listen to a RFCOMM UUID or channel. It returns the socket fd from which + * btsock_connect_signal can be read out when a remote device connected. + * If neither a UUID nor a channel is provided, a channel will be allocated + * and a service record can be created providing the channel number to + * create_sdp_record(...) in bt_sdp. + */ + bt_status_t (*listen)(btsock_type_t type, const char* service_name, + const uint8_t* service_uuid, int channel, int* sock_fd, int flags); + + /** + * Connect to a RFCOMM UUID channel of remote device, It returns the socket fd from which + * the btsock_connect_signal and a new socket fd to be accepted can be read out when connected + */ + bt_status_t (*connect)(const bt_bdaddr_t *bd_addr, btsock_type_t type, const uint8_t* uuid, + int channel, int* sock_fd, int flags); + + /* + * get socket option of rfcomm channel socket. + */ + bt_status_t (*get_sock_opt)(btsock_type_t type, int channel, btsock_option_type_t option_name, + void *option_value, int *option_len); + /* + + * set socket option of rfcomm channel socket. + */ + bt_status_t (*set_sock_opt)(btsock_type_t type, int channel, btsock_option_type_t option_name, + void *option_value, int option_len); + +} btsock_interface_t; + +__END_DECLS + diff --git a/third_party/android_hardware_libhardware/include/hardware/camera.h b/third_party/android_hardware_libhardware/include/hardware/camera.h new file mode 100644 index 00000000000000..b1f18fffce38f3 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/camera.h @@ -0,0 +1,298 @@ +/* + * Copyright (C) 2010-2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_CAMERA_H +#define ANDROID_INCLUDE_CAMERA_H + +#include "camera_common.h" + +/** + * Camera device HAL, initial version [ CAMERA_DEVICE_API_VERSION_1_0 ] + * + * DEPRECATED. New devices should use Camera HAL v3.2 or newer. + * + * Supports the android.hardware.Camera API, and the android.hardware.camera2 + * API in legacy mode only. + * + * Camera devices that support this version of the HAL must return a value in + * the range HARDWARE_DEVICE_API_VERSION(0,0)-(1,FF) in + * camera_device_t.common.version. CAMERA_DEVICE_API_VERSION_1_0 is the + * recommended value. + * + * Camera modules that implement version 2.0 or higher of camera_module_t must + * also return the value of camera_device_t.common.version in + * camera_info_t.device_version. + * + * See camera_common.h for more details. + */ + +__BEGIN_DECLS + +struct camera_memory; +typedef void (*camera_release_memory)(struct camera_memory *mem); + +typedef struct camera_memory { + void *data; + size_t size; + void *handle; + camera_release_memory release; +} camera_memory_t; + +typedef camera_memory_t* (*camera_request_memory)(int fd, size_t buf_size, unsigned int num_bufs, + void *user); + +typedef void (*camera_notify_callback)(int32_t msg_type, + int32_t ext1, + int32_t ext2, + void *user); + +typedef void (*camera_data_callback)(int32_t msg_type, + const camera_memory_t *data, unsigned int index, + camera_frame_metadata_t *metadata, void *user); + +typedef void (*camera_data_timestamp_callback)(int64_t timestamp, + int32_t msg_type, + const camera_memory_t *data, unsigned int index, + void *user); + +#define HAL_CAMERA_PREVIEW_WINDOW_TAG 0xcafed00d + +typedef struct preview_stream_ops { + int (*dequeue_buffer)(struct preview_stream_ops* w, + buffer_handle_t** buffer, int *stride); + int (*enqueue_buffer)(struct preview_stream_ops* w, + buffer_handle_t* buffer); + int (*cancel_buffer)(struct preview_stream_ops* w, + buffer_handle_t* buffer); + int (*set_buffer_count)(struct preview_stream_ops* w, int count); + int (*set_buffers_geometry)(struct preview_stream_ops* pw, + int w, int h, int format); + int (*set_crop)(struct preview_stream_ops *w, + int left, int top, int right, int bottom); + int (*set_usage)(struct preview_stream_ops* w, int usage); + int (*set_swap_interval)(struct preview_stream_ops *w, int interval); + int (*get_min_undequeued_buffer_count)(const struct preview_stream_ops *w, + int *count); + int (*lock_buffer)(struct preview_stream_ops* w, + buffer_handle_t* buffer); + // Timestamps are measured in nanoseconds, and must be comparable + // and monotonically increasing between two frames in the same + // preview stream. They do not need to be comparable between + // consecutive or parallel preview streams, cameras, or app runs. + int (*set_timestamp)(struct preview_stream_ops *w, int64_t timestamp); +} preview_stream_ops_t; + +struct camera_device; +typedef struct camera_device_ops { + /** Set the ANativeWindow to which preview frames are sent */ + int (*set_preview_window)(struct camera_device *, + struct preview_stream_ops *window); + + /** Set the notification and data callbacks */ + void (*set_callbacks)(struct camera_device *, + camera_notify_callback notify_cb, + camera_data_callback data_cb, + camera_data_timestamp_callback data_cb_timestamp, + camera_request_memory get_memory, + void *user); + + /** + * The following three functions all take a msg_type, which is a bitmask of + * the messages defined in include/ui/Camera.h + */ + + /** + * Enable a message, or set of messages. + */ + void (*enable_msg_type)(struct camera_device *, int32_t msg_type); + + /** + * Disable a message, or a set of messages. + * + * Once received a call to disableMsgType(CAMERA_MSG_VIDEO_FRAME), camera + * HAL should not rely on its client to call releaseRecordingFrame() to + * release video recording frames sent out by the cameral HAL before and + * after the disableMsgType(CAMERA_MSG_VIDEO_FRAME) call. Camera HAL + * clients must not modify/access any video recording frame after calling + * disableMsgType(CAMERA_MSG_VIDEO_FRAME). + */ + void (*disable_msg_type)(struct camera_device *, int32_t msg_type); + + /** + * Query whether a message, or a set of messages, is enabled. Note that + * this is operates as an AND, if any of the messages queried are off, this + * will return false. + */ + int (*msg_type_enabled)(struct camera_device *, int32_t msg_type); + + /** + * Start preview mode. + */ + int (*start_preview)(struct camera_device *); + + /** + * Stop a previously started preview. + */ + void (*stop_preview)(struct camera_device *); + + /** + * Returns true if preview is enabled. + */ + int (*preview_enabled)(struct camera_device *); + + /** + * Request the camera HAL to store meta data or real YUV data in the video + * buffers sent out via CAMERA_MSG_VIDEO_FRAME for a recording session. If + * it is not called, the default camera HAL behavior is to store real YUV + * data in the video buffers. + * + * This method should be called before startRecording() in order to be + * effective. + * + * If meta data is stored in the video buffers, it is up to the receiver of + * the video buffers to interpret the contents and to find the actual frame + * data with the help of the meta data in the buffer. How this is done is + * outside of the scope of this method. + * + * Some camera HALs may not support storing meta data in the video buffers, + * but all camera HALs should support storing real YUV data in the video + * buffers. If the camera HAL does not support storing the meta data in the + * video buffers when it is requested to do do, INVALID_OPERATION must be + * returned. It is very useful for the camera HAL to pass meta data rather + * than the actual frame data directly to the video encoder, since the + * amount of the uncompressed frame data can be very large if video size is + * large. + * + * @param enable if true to instruct the camera HAL to store + * meta data in the video buffers; false to instruct + * the camera HAL to store real YUV data in the video + * buffers. + * + * @return OK on success. + */ + int (*store_meta_data_in_buffers)(struct camera_device *, int enable); + + /** + * Start record mode. When a record image is available, a + * CAMERA_MSG_VIDEO_FRAME message is sent with the corresponding + * frame. Every record frame must be released by a camera HAL client via + * releaseRecordingFrame() before the client calls + * disableMsgType(CAMERA_MSG_VIDEO_FRAME). After the client calls + * disableMsgType(CAMERA_MSG_VIDEO_FRAME), it is the camera HAL's + * responsibility to manage the life-cycle of the video recording frames, + * and the client must not modify/access any video recording frames. + */ + int (*start_recording)(struct camera_device *); + + /** + * Stop a previously started recording. + */ + void (*stop_recording)(struct camera_device *); + + /** + * Returns true if recording is enabled. + */ + int (*recording_enabled)(struct camera_device *); + + /** + * Release a record frame previously returned by CAMERA_MSG_VIDEO_FRAME. + * + * It is camera HAL client's responsibility to release video recording + * frames sent out by the camera HAL before the camera HAL receives a call + * to disableMsgType(CAMERA_MSG_VIDEO_FRAME). After it receives the call to + * disableMsgType(CAMERA_MSG_VIDEO_FRAME), it is the camera HAL's + * responsibility to manage the life-cycle of the video recording frames. + */ + void (*release_recording_frame)(struct camera_device *, + const void *opaque); + + /** + * Start auto focus, the notification callback routine is called with + * CAMERA_MSG_FOCUS once when focusing is complete. autoFocus() will be + * called again if another auto focus is needed. + */ + int (*auto_focus)(struct camera_device *); + + /** + * Cancels auto-focus function. If the auto-focus is still in progress, + * this function will cancel it. Whether the auto-focus is in progress or + * not, this function will return the focus position to the default. If + * the camera does not support auto-focus, this is a no-op. + */ + int (*cancel_auto_focus)(struct camera_device *); + + /** + * Take a picture. + */ + int (*take_picture)(struct camera_device *); + + /** + * Cancel a picture that was started with takePicture. Calling this method + * when no picture is being taken is a no-op. + */ + int (*cancel_picture)(struct camera_device *); + + /** + * Set the camera parameters. This returns BAD_VALUE if any parameter is + * invalid or not supported. + */ + int (*set_parameters)(struct camera_device *, const char *parms); + + /** Retrieve the camera parameters. The buffer returned by the camera HAL + must be returned back to it with put_parameters, if put_parameters + is not NULL. + */ + char *(*get_parameters)(struct camera_device *); + + /** The camera HAL uses its own memory to pass us the parameters when we + call get_parameters. Use this function to return the memory back to + the camera HAL, if put_parameters is not NULL. If put_parameters + is NULL, then you have to use free() to release the memory. + */ + void (*put_parameters)(struct camera_device *, char *); + + /** + * Send command to camera driver. + */ + int (*send_command)(struct camera_device *, + int32_t cmd, int32_t arg1, int32_t arg2); + + /** + * Release the hardware resources owned by this object. Note that this is + * *not* done in the destructor. + */ + void (*release)(struct camera_device *); + + /** + * Dump state of the camera hardware + */ + int (*dump)(struct camera_device *, int fd); +} camera_device_ops_t; + +typedef struct camera_device { + /** + * camera_device.common.version must be in the range + * HARDWARE_DEVICE_API_VERSION(0,0)-(1,FF). CAMERA_DEVICE_API_VERSION_1_0 is + * recommended. + */ + hw_device_t common; + camera_device_ops_t *ops; + void *priv; +} camera_device_t; + +__END_DECLS + +#endif /* #ifdef ANDROID_INCLUDE_CAMERA_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/camera2.h b/third_party/android_hardware_libhardware/include/hardware/camera2.h new file mode 100644 index 00000000000000..d920d4b65cbd05 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/camera2.h @@ -0,0 +1,839 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_CAMERA2_H +#define ANDROID_INCLUDE_CAMERA2_H + +#include "camera_common.h" +#include "system/camera_metadata.h" + +/** + * Camera device HAL 2.1 [ CAMERA_DEVICE_API_VERSION_2_0, CAMERA_DEVICE_API_VERSION_2_1 ] + * + * DEPRECATED. New devices should use Camera HAL v3.2 or newer. + * + * Supports the android.hardware.Camera API, and the android.hardware.camera2 + * API in legacy mode only. + * + * Camera devices that support this version of the HAL must return + * CAMERA_DEVICE_API_VERSION_2_1 in camera_device_t.common.version and in + * camera_info_t.device_version (from camera_module_t.get_camera_info). + * + * Camera modules that may contain version 2.x devices must implement at least + * version 2.0 of the camera module interface (as defined by + * camera_module_t.common.module_api_version). + * + * See camera_common.h for more versioning details. + * + * Version history: + * + * 2.0: CAMERA_DEVICE_API_VERSION_2_0. Initial release (Android 4.2): + * - Sufficient for implementing existing android.hardware.Camera API. + * - Allows for ZSL queue in camera service layer + * - Not tested for any new features such manual capture control, + * Bayer RAW capture, reprocessing of RAW data. + * + * 2.1: CAMERA_DEVICE_API_VERSION_2_1. Support per-device static metadata: + * - Add get_instance_metadata() method to retrieve metadata that is fixed + * after device open, but may be variable between open() calls. + */ + +__BEGIN_DECLS + +struct camera2_device; + +/********************************************************************** + * + * Input/output stream buffer queue interface definitions + * + */ + +/** + * Output image stream queue interface. A set of these methods is provided to + * the HAL device in allocate_stream(), and are used to interact with the + * gralloc buffer queue for that stream. They may not be called until after + * allocate_stream returns. + */ +typedef struct camera2_stream_ops { + /** + * Get a buffer to fill from the queue. The size and format of the buffer + * are fixed for a given stream (defined in allocate_stream), and the stride + * should be queried from the platform gralloc module. The gralloc buffer + * will have been allocated based on the usage flags provided by + * allocate_stream, and will be locked for use. + */ + int (*dequeue_buffer)(const struct camera2_stream_ops* w, + buffer_handle_t** buffer); + + /** + * Push a filled buffer to the stream to be used by the consumer. + * + * The timestamp represents the time at start of exposure of the first row + * of the image; it must be from a monotonic clock, and is measured in + * nanoseconds. The timestamps do not need to be comparable between + * different cameras, or consecutive instances of the same camera. However, + * they must be comparable between streams from the same camera. If one + * capture produces buffers for multiple streams, each stream must have the + * same timestamp for that buffer, and that timestamp must match the + * timestamp in the output frame metadata. + */ + int (*enqueue_buffer)(const struct camera2_stream_ops* w, + int64_t timestamp, + buffer_handle_t* buffer); + /** + * Return a buffer to the queue without marking it as filled. + */ + int (*cancel_buffer)(const struct camera2_stream_ops* w, + buffer_handle_t* buffer); + /** + * Set the crop window for subsequently enqueued buffers. The parameters are + * measured in pixels relative to the buffer width and height. + */ + int (*set_crop)(const struct camera2_stream_ops *w, + int left, int top, int right, int bottom); + +} camera2_stream_ops_t; + +/** + * Temporary definition during transition. + * + * These formats will be removed and replaced with + * HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED. To maximize forward compatibility, + * HAL implementations are strongly recommended to treat FORMAT_OPAQUE and + * FORMAT_ZSL as equivalent to HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED, and + * return HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED in the format_actual output + * parameter of allocate_stream, allowing the gralloc module to select the + * specific format based on the usage flags from the camera and the stream + * consumer. + */ +enum { + CAMERA2_HAL_PIXEL_FORMAT_OPAQUE = HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED, + CAMERA2_HAL_PIXEL_FORMAT_ZSL = -1 +}; + +/** + * Transport header for compressed JPEG buffers in output streams. + * + * To capture JPEG images, a stream is created using the pixel format + * HAL_PIXEL_FORMAT_BLOB, and the static metadata field android.jpeg.maxSize is + * used as the buffer size. Since compressed JPEG images are of variable size, + * the HAL needs to include the final size of the compressed image using this + * structure inside the output stream buffer. The JPEG blob ID field must be set + * to CAMERA2_JPEG_BLOB_ID. + * + * Transport header should be at the end of the JPEG output stream buffer. That + * means the jpeg_blob_id must start at byte[android.jpeg.maxSize - + * sizeof(camera2_jpeg_blob)]. Any HAL using this transport header must + * account for it in android.jpeg.maxSize. The JPEG data itself starts at + * byte[0] and should be jpeg_size bytes long. + */ +typedef struct camera2_jpeg_blob { + uint16_t jpeg_blob_id; + uint32_t jpeg_size; +}; + +enum { + CAMERA2_JPEG_BLOB_ID = 0x00FF +}; + +/** + * Input reprocess stream queue management. A set of these methods is provided + * to the HAL device in allocate_reprocess_stream(); they are used to interact + * with the reprocess stream's input gralloc buffer queue. + */ +typedef struct camera2_stream_in_ops { + /** + * Get the next buffer of image data to reprocess. The width, height, and + * format of the buffer is fixed in allocate_reprocess_stream(), and the + * stride and other details should be queried from the platform gralloc + * module as needed. The buffer will already be locked for use. + */ + int (*acquire_buffer)(const struct camera2_stream_in_ops *w, + buffer_handle_t** buffer); + /** + * Return a used buffer to the buffer queue for reuse. + */ + int (*release_buffer)(const struct camera2_stream_in_ops *w, + buffer_handle_t* buffer); + +} camera2_stream_in_ops_t; + +/********************************************************************** + * + * Metadata queue management, used for requests sent to HAL module, and for + * frames produced by the HAL. + * + */ + +enum { + CAMERA2_REQUEST_QUEUE_IS_BOTTOMLESS = -1 +}; + +/** + * Request input queue protocol: + * + * The framework holds the queue and its contents. At start, the queue is empty. + * + * 1. When the first metadata buffer is placed into the queue, the framework + * signals the device by calling notify_request_queue_not_empty(). + * + * 2. After receiving notify_request_queue_not_empty, the device must call + * dequeue() once it's ready to handle the next buffer. + * + * 3. Once the device has processed a buffer, and is ready for the next buffer, + * it must call dequeue() again instead of waiting for a notification. If + * there are no more buffers available, dequeue() will return NULL. After + * this point, when a buffer becomes available, the framework must call + * notify_request_queue_not_empty() again. If the device receives a NULL + * return from dequeue, it does not need to query the queue again until a + * notify_request_queue_not_empty() call is received from the source. + * + * 4. If the device calls buffer_count() and receives 0, this does not mean that + * the framework will provide a notify_request_queue_not_empty() call. The + * framework will only provide such a notification after the device has + * received a NULL from dequeue, or on initial startup. + * + * 5. The dequeue() call in response to notify_request_queue_not_empty() may be + * on the same thread as the notify_request_queue_not_empty() call, and may + * be performed from within the notify call. + * + * 6. All dequeued request buffers must be returned to the framework by calling + * free_request, including when errors occur, a device flush is requested, or + * when the device is shutting down. + */ +typedef struct camera2_request_queue_src_ops { + /** + * Get the count of request buffers pending in the queue. May return + * CAMERA2_REQUEST_QUEUE_IS_BOTTOMLESS if a repeating request (stream + * request) is currently configured. Calling this method has no effect on + * whether the notify_request_queue_not_empty() method will be called by the + * framework. + */ + int (*request_count)(const struct camera2_request_queue_src_ops *q); + + /** + * Get a metadata buffer from the framework. Returns OK if there is no + * error. If the queue is empty, returns NULL in buffer. In that case, the + * device must wait for a notify_request_queue_not_empty() message before + * attempting to dequeue again. Buffers obtained in this way must be + * returned to the framework with free_request(). + */ + int (*dequeue_request)(const struct camera2_request_queue_src_ops *q, + camera_metadata_t **buffer); + /** + * Return a metadata buffer to the framework once it has been used, or if + * an error or shutdown occurs. + */ + int (*free_request)(const struct camera2_request_queue_src_ops *q, + camera_metadata_t *old_buffer); + +} camera2_request_queue_src_ops_t; + +/** + * Frame output queue protocol: + * + * The framework holds the queue and its contents. At start, the queue is empty. + * + * 1. When the device is ready to fill an output metadata frame, it must dequeue + * a metadata buffer of the required size. + * + * 2. It should then fill the metadata buffer, and place it on the frame queue + * using enqueue_frame. The framework takes ownership of the frame. + * + * 3. In case of an error, a request to flush the pipeline, or shutdown, the + * device must return any affected dequeued frames to the framework by + * calling cancel_frame. + */ +typedef struct camera2_frame_queue_dst_ops { + /** + * Get an empty metadata buffer to fill from the framework. The new metadata + * buffer will have room for entries number of metadata entries, plus + * data_bytes worth of extra storage. Frames dequeued here must be returned + * to the framework with either cancel_frame or enqueue_frame. + */ + int (*dequeue_frame)(const struct camera2_frame_queue_dst_ops *q, + size_t entries, size_t data_bytes, + camera_metadata_t **buffer); + + /** + * Return a dequeued metadata buffer to the framework for reuse; do not mark it as + * filled. Use when encountering errors, or flushing the internal request queue. + */ + int (*cancel_frame)(const struct camera2_frame_queue_dst_ops *q, + camera_metadata_t *buffer); + + /** + * Place a completed metadata frame on the frame output queue. + */ + int (*enqueue_frame)(const struct camera2_frame_queue_dst_ops *q, + camera_metadata_t *buffer); + +} camera2_frame_queue_dst_ops_t; + +/********************************************************************** + * + * Notification callback and message definition, and trigger definitions + * + */ + +/** + * Asynchronous notification callback from the HAL, fired for various + * reasons. Only for information independent of frame capture, or that require + * specific timing. The user pointer must be the same one that was passed to the + * device in set_notify_callback(). + */ +typedef void (*camera2_notify_callback)(int32_t msg_type, + int32_t ext1, + int32_t ext2, + int32_t ext3, + void *user); + +/** + * Possible message types for camera2_notify_callback + */ +enum { + /** + * An error has occurred. Argument ext1 contains the error code, and + * ext2 and ext3 contain any error-specific information. + */ + CAMERA2_MSG_ERROR = 0x0001, + /** + * The exposure of a given request has begun. Argument ext1 contains the + * frame number, and ext2 and ext3 contain the low-order and high-order + * bytes of the timestamp for when exposure began. + * (timestamp = (ext3 << 32 | ext2)) + */ + CAMERA2_MSG_SHUTTER = 0x0010, + /** + * The autofocus routine has changed state. Argument ext1 contains the new + * state; the values are the same as those for the metadata field + * android.control.afState. Ext2 contains the latest trigger ID passed to + * trigger_action(CAMERA2_TRIGGER_AUTOFOCUS) or + * trigger_action(CAMERA2_TRIGGER_CANCEL_AUTOFOCUS), or 0 if trigger has not + * been called with either of those actions. + */ + CAMERA2_MSG_AUTOFOCUS = 0x0020, + /** + * The autoexposure routine has changed state. Argument ext1 contains the + * new state; the values are the same as those for the metadata field + * android.control.aeState. Ext2 contains the latest trigger ID value passed to + * trigger_action(CAMERA2_TRIGGER_PRECAPTURE_METERING), or 0 if that method + * has not been called. + */ + CAMERA2_MSG_AUTOEXPOSURE = 0x0021, + /** + * The auto-whitebalance routine has changed state. Argument ext1 contains + * the new state; the values are the same as those for the metadata field + * android.control.awbState. Ext2 contains the latest trigger ID passed to + * trigger_action(CAMERA2_TRIGGER_PRECAPTURE_METERING), or 0 if that method + * has not been called. + */ + CAMERA2_MSG_AUTOWB = 0x0022 +}; + +/** + * Error codes for CAMERA_MSG_ERROR + */ +enum { + /** + * A serious failure occured. Camera device may not work without reboot, and + * no further frames or buffer streams will be produced by the + * device. Device should be treated as closed. + */ + CAMERA2_MSG_ERROR_HARDWARE = 0x0001, + /** + * A serious failure occured. No further frames or buffer streams will be + * produced by the device. Device should be treated as closed. The client + * must reopen the device to use it again. + */ + CAMERA2_MSG_ERROR_DEVICE, + /** + * An error has occurred in processing a request. No output (metadata or + * buffers) will be produced for this request. ext2 contains the frame + * number of the request. Subsequent requests are unaffected, and the device + * remains operational. + */ + CAMERA2_MSG_ERROR_REQUEST, + /** + * An error has occurred in producing an output frame metadata buffer for a + * request, but image buffers for it will still be available. Subsequent + * requests are unaffected, and the device remains operational. ext2 + * contains the frame number of the request. + */ + CAMERA2_MSG_ERROR_FRAME, + /** + * An error has occurred in placing an output buffer into a stream for a + * request. The frame metadata and other buffers may still be + * available. Subsequent requests are unaffected, and the device remains + * operational. ext2 contains the frame number of the request, and ext3 + * contains the stream id. + */ + CAMERA2_MSG_ERROR_STREAM, + /** + * Number of error types + */ + CAMERA2_MSG_NUM_ERRORS +}; + +/** + * Possible trigger ids for trigger_action() + */ +enum { + /** + * Trigger an autofocus cycle. The effect of the trigger depends on the + * autofocus mode in effect when the trigger is received, which is the mode + * listed in the latest capture request to be dequeued by the HAL. If the + * mode is OFF, EDOF, or FIXED, the trigger has no effect. In AUTO, MACRO, + * or CONTINUOUS_* modes, see below for the expected behavior. The state of + * the autofocus cycle can be tracked in android.control.afMode and the + * corresponding notifications. + * + ** + * In AUTO or MACRO mode, the AF state transitions (and notifications) + * when calling with trigger ID = N with the previous ID being K are: + * + * Initial state Transitions + * INACTIVE (K) -> ACTIVE_SCAN (N) -> AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * AF_FOCUSED (K) -> ACTIVE_SCAN (N) -> AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * AF_NOT_FOCUSED (K) -> ACTIVE_SCAN (N) -> AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * ACTIVE_SCAN (K) -> AF_FOCUSED(N) or AF_NOT_FOCUSED(N) + * PASSIVE_SCAN (K) Not used in AUTO/MACRO mode + * PASSIVE_FOCUSED (K) Not used in AUTO/MACRO mode + * + ** + * In CONTINUOUS_PICTURE mode, triggering AF must lock the AF to the current + * lens position and transition the AF state to either AF_FOCUSED or + * NOT_FOCUSED. If a passive scan is underway, that scan must complete and + * then lock the lens position and change AF state. TRIGGER_CANCEL_AUTOFOCUS + * will allow the AF to restart its operation. + * + * Initial state Transitions + * INACTIVE (K) -> immediate AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * PASSIVE_FOCUSED (K) -> immediate AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * PASSIVE_SCAN (K) -> AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * AF_FOCUSED (K) no effect except to change next notification ID to N + * AF_NOT_FOCUSED (K) no effect except to change next notification ID to N + * + ** + * In CONTINUOUS_VIDEO mode, triggering AF must lock the AF to the current + * lens position and transition the AF state to either AF_FOCUSED or + * NOT_FOCUSED. If a passive scan is underway, it must immediately halt, in + * contrast with CONTINUOUS_PICTURE mode. TRIGGER_CANCEL_AUTOFOCUS will + * allow the AF to restart its operation. + * + * Initial state Transitions + * INACTIVE (K) -> immediate AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * PASSIVE_FOCUSED (K) -> immediate AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * PASSIVE_SCAN (K) -> immediate AF_FOCUSED (N) or AF_NOT_FOCUSED (N) + * AF_FOCUSED (K) no effect except to change next notification ID to N + * AF_NOT_FOCUSED (K) no effect except to change next notification ID to N + * + * Ext1 is an ID that must be returned in subsequent auto-focus state change + * notifications through camera2_notify_callback() and stored in + * android.control.afTriggerId. + */ + CAMERA2_TRIGGER_AUTOFOCUS = 0x0001, + /** + * Send a cancel message to the autofocus algorithm. The effect of the + * cancellation depends on the autofocus mode in effect when the trigger is + * received, which is the mode listed in the latest capture request to be + * dequeued by the HAL. If the AF mode is OFF or EDOF, the cancel has no + * effect. For other modes, the lens should return to its default position, + * any current autofocus scan must be canceled, and the AF state should be + * set to INACTIVE. + * + * The state of the autofocus cycle can be tracked in android.control.afMode + * and the corresponding notification. Continuous autofocus modes may resume + * focusing operations thereafter exactly as if the camera had just been set + * to a continuous AF mode. + * + * Ext1 is an ID that must be returned in subsequent auto-focus state change + * notifications through camera2_notify_callback() and stored in + * android.control.afTriggerId. + */ + CAMERA2_TRIGGER_CANCEL_AUTOFOCUS, + /** + * Trigger a pre-capture metering cycle, which may include firing the flash + * to determine proper capture parameters. Typically, this trigger would be + * fired for a half-depress of a camera shutter key, or before a snapshot + * capture in general. The state of the metering cycle can be tracked in + * android.control.aeMode and the corresponding notification. If the + * auto-exposure mode is OFF, the trigger does nothing. + * + * Ext1 is an ID that must be returned in subsequent + * auto-exposure/auto-white balance state change notifications through + * camera2_notify_callback() and stored in android.control.aePrecaptureId. + */ + CAMERA2_TRIGGER_PRECAPTURE_METERING +}; + +/** + * Possible template types for construct_default_request() + */ +enum { + /** + * Standard camera preview operation with 3A on auto. + */ + CAMERA2_TEMPLATE_PREVIEW = 1, + /** + * Standard camera high-quality still capture with 3A and flash on auto. + */ + CAMERA2_TEMPLATE_STILL_CAPTURE, + /** + * Standard video recording plus preview with 3A on auto, torch off. + */ + CAMERA2_TEMPLATE_VIDEO_RECORD, + /** + * High-quality still capture while recording video. Application will + * include preview, video record, and full-resolution YUV or JPEG streams in + * request. Must not cause stuttering on video stream. 3A on auto. + */ + CAMERA2_TEMPLATE_VIDEO_SNAPSHOT, + /** + * Zero-shutter-lag mode. Application will request preview and + * full-resolution data for each frame, and reprocess it to JPEG when a + * still image is requested by user. Settings should provide highest-quality + * full-resolution images without compromising preview frame rate. 3A on + * auto. + */ + CAMERA2_TEMPLATE_ZERO_SHUTTER_LAG, + + /* Total number of templates */ + CAMERA2_TEMPLATE_COUNT +}; + + +/********************************************************************** + * + * Camera device operations + * + */ +typedef struct camera2_device_ops { + + /********************************************************************** + * Request and frame queue setup and management methods + */ + + /** + * Pass in input request queue interface methods. + */ + int (*set_request_queue_src_ops)(const struct camera2_device *, + const camera2_request_queue_src_ops_t *request_src_ops); + + /** + * Notify device that the request queue is no longer empty. Must only be + * called when the first buffer is added a new queue, or after the source + * has returned NULL in response to a dequeue call. + */ + int (*notify_request_queue_not_empty)(const struct camera2_device *); + + /** + * Pass in output frame queue interface methods + */ + int (*set_frame_queue_dst_ops)(const struct camera2_device *, + const camera2_frame_queue_dst_ops_t *frame_dst_ops); + + /** + * Number of camera requests being processed by the device at the moment + * (captures/reprocesses that have had their request dequeued, but have not + * yet been enqueued onto output pipeline(s) ). No streams may be released + * by the framework until the in-progress count is 0. + */ + int (*get_in_progress_count)(const struct camera2_device *); + + /** + * Flush all in-progress captures. This includes all dequeued requests + * (regular or reprocessing) that have not yet placed any outputs into a + * stream or the frame queue. Partially completed captures must be completed + * normally. No new requests may be dequeued from the request queue until + * the flush completes. + */ + int (*flush_captures_in_progress)(const struct camera2_device *); + + /** + * Create a filled-in default request for standard camera use cases. + * + * The device must return a complete request that is configured to meet the + * requested use case, which must be one of the CAMERA2_TEMPLATE_* + * enums. All request control fields must be included, except for + * android.request.outputStreams. + * + * The metadata buffer returned must be allocated with + * allocate_camera_metadata. The framework takes ownership of the buffer. + */ + int (*construct_default_request)(const struct camera2_device *, + int request_template, + camera_metadata_t **request); + + /********************************************************************** + * Stream management + */ + + /** + * allocate_stream: + * + * Allocate a new output stream for use, defined by the output buffer width, + * height, target, and possibly the pixel format. Returns the new stream's + * ID, gralloc usage flags, minimum queue buffer count, and possibly the + * pixel format, on success. Error conditions: + * + * - Requesting a width/height/format combination not listed as + * supported by the sensor's static characteristics + * + * - Asking for too many streams of a given format type (2 bayer raw + * streams, for example). + * + * Input parameters: + * + * - width, height, format: Specification for the buffers to be sent through + * this stream. Format is a value from the HAL_PIXEL_FORMAT_* list. If + * HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED is used, then the platform + * gralloc module will select a format based on the usage flags provided + * by the camera HAL and the consumer of the stream. The camera HAL should + * inspect the buffers handed to it in the register_stream_buffers call to + * obtain the implementation-specific format if necessary. + * + * - stream_ops: A structure of function pointers for obtaining and queuing + * up buffers for this stream. The underlying stream will be configured + * based on the usage and max_buffers outputs. The methods in this + * structure may not be called until after allocate_stream returns. + * + * Output parameters: + * + * - stream_id: An unsigned integer identifying this stream. This value is + * used in incoming requests to identify the stream, and in releasing the + * stream. + * + * - usage: The gralloc usage mask needed by the HAL device for producing + * the requested type of data. This is used in allocating new gralloc + * buffers for the stream buffer queue. + * + * - max_buffers: The maximum number of buffers the HAL device may need to + * have dequeued at the same time. The device may not dequeue more buffers + * than this value at the same time. + * + */ + int (*allocate_stream)( + const struct camera2_device *, + // inputs + uint32_t width, + uint32_t height, + int format, + const camera2_stream_ops_t *stream_ops, + // outputs + uint32_t *stream_id, + uint32_t *format_actual, // IGNORED, will be removed + uint32_t *usage, + uint32_t *max_buffers); + + /** + * Register buffers for a given stream. This is called after a successful + * allocate_stream call, and before the first request referencing the stream + * is enqueued. This method is intended to allow the HAL device to map or + * otherwise prepare the buffers for later use. num_buffers is guaranteed to + * be at least max_buffers (from allocate_stream), but may be larger. The + * buffers will already be locked for use. At the end of the call, all the + * buffers must be ready to be returned to the queue. If the stream format + * was set to HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED, the camera HAL should + * inspect the passed-in buffers here to determine any platform-private + * pixel format information. + */ + int (*register_stream_buffers)( + const struct camera2_device *, + uint32_t stream_id, + int num_buffers, + buffer_handle_t *buffers); + + /** + * Release a stream. Returns an error if called when get_in_progress_count + * is non-zero, or if the stream id is invalid. + */ + int (*release_stream)( + const struct camera2_device *, + uint32_t stream_id); + + /** + * allocate_reprocess_stream: + * + * Allocate a new input stream for use, defined by the output buffer width, + * height, and the pixel format. Returns the new stream's ID, gralloc usage + * flags, and required simultaneously acquirable buffer count, on + * success. Error conditions: + * + * - Requesting a width/height/format combination not listed as + * supported by the sensor's static characteristics + * + * - Asking for too many reprocessing streams to be configured at once. + * + * Input parameters: + * + * - width, height, format: Specification for the buffers to be sent through + * this stream. Format must be a value from the HAL_PIXEL_FORMAT_* list. + * + * - reprocess_stream_ops: A structure of function pointers for acquiring + * and releasing buffers for this stream. The underlying stream will be + * configured based on the usage and max_buffers outputs. + * + * Output parameters: + * + * - stream_id: An unsigned integer identifying this stream. This value is + * used in incoming requests to identify the stream, and in releasing the + * stream. These ids are numbered separately from the input stream ids. + * + * - consumer_usage: The gralloc usage mask needed by the HAL device for + * consuming the requested type of data. This is used in allocating new + * gralloc buffers for the stream buffer queue. + * + * - max_buffers: The maximum number of buffers the HAL device may need to + * have acquired at the same time. The device may not have more buffers + * acquired at the same time than this value. + * + */ + int (*allocate_reprocess_stream)(const struct camera2_device *, + uint32_t width, + uint32_t height, + uint32_t format, + const camera2_stream_in_ops_t *reprocess_stream_ops, + // outputs + uint32_t *stream_id, + uint32_t *consumer_usage, + uint32_t *max_buffers); + + /** + * allocate_reprocess_stream_from_stream: + * + * Allocate a new input stream for use, which will use the buffers allocated + * for an existing output stream. That is, after the HAL enqueues a buffer + * onto the output stream, it may see that same buffer handed to it from + * this input reprocessing stream. After the HAL releases the buffer back to + * the reprocessing stream, it will be returned to the output queue for + * reuse. + * + * Error conditions: + * + * - Using an output stream of unsuitable size/format for the basis of the + * reprocessing stream. + * + * - Attempting to allocatee too many reprocessing streams at once. + * + * Input parameters: + * + * - output_stream_id: The ID of an existing output stream which has + * a size and format suitable for reprocessing. + * + * - reprocess_stream_ops: A structure of function pointers for acquiring + * and releasing buffers for this stream. The underlying stream will use + * the same graphics buffer handles as the output stream uses. + * + * Output parameters: + * + * - stream_id: An unsigned integer identifying this stream. This value is + * used in incoming requests to identify the stream, and in releasing the + * stream. These ids are numbered separately from the input stream ids. + * + * The HAL client must always release the reprocessing stream before it + * releases the output stream it is based on. + * + */ + int (*allocate_reprocess_stream_from_stream)(const struct camera2_device *, + uint32_t output_stream_id, + const camera2_stream_in_ops_t *reprocess_stream_ops, + // outputs + uint32_t *stream_id); + + /** + * Release a reprocessing stream. Returns an error if called when + * get_in_progress_count is non-zero, or if the stream id is not + * valid. + */ + int (*release_reprocess_stream)( + const struct camera2_device *, + uint32_t stream_id); + + /********************************************************************** + * Miscellaneous methods + */ + + /** + * Trigger asynchronous activity. This is used for triggering special + * behaviors of the camera 3A routines when they are in use. See the + * documentation for CAMERA2_TRIGGER_* above for details of the trigger ids + * and their arguments. + */ + int (*trigger_action)(const struct camera2_device *, + uint32_t trigger_id, + int32_t ext1, + int32_t ext2); + + /** + * Notification callback setup + */ + int (*set_notify_callback)(const struct camera2_device *, + camera2_notify_callback notify_cb, + void *user); + + /** + * Get methods to query for vendor extension metadata tag infomation. May + * set ops to NULL if no vendor extension tags are defined. + */ + int (*get_metadata_vendor_tag_ops)(const struct camera2_device*, + vendor_tag_query_ops_t **ops); + + /** + * Dump state of the camera hardware + */ + int (*dump)(const struct camera2_device *, int fd); + + /** + * Get device-instance-specific metadata. This metadata must be constant for + * a single instance of the camera device, but may be different between + * open() calls. The returned camera_metadata pointer must be valid until + * the device close() method is called. + * + * Version information: + * + * CAMERA_DEVICE_API_VERSION_2_0: + * + * Not available. Framework may not access this function pointer. + * + * CAMERA_DEVICE_API_VERSION_2_1: + * + * Valid. Can be called by the framework. + * + */ + int (*get_instance_metadata)(const struct camera2_device *, + camera_metadata **instance_metadata); + +} camera2_device_ops_t; + +/********************************************************************** + * + * Camera device definition + * + */ +typedef struct camera2_device { + /** + * common.version must equal CAMERA_DEVICE_API_VERSION_2_0 to identify + * this device as implementing version 2.0 of the camera device HAL. + */ + hw_device_t common; + camera2_device_ops_t *ops; + void *priv; +} camera2_device_t; + +__END_DECLS + +#endif /* #ifdef ANDROID_INCLUDE_CAMERA2_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/camera3.h b/third_party/android_hardware_libhardware/include/hardware/camera3.h new file mode 100644 index 00000000000000..3ef6d6fadae51c --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/camera3.h @@ -0,0 +1,3077 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_CAMERA3_H +#define ANDROID_INCLUDE_CAMERA3_H + +#include +#include "camera_common.h" + +/** + * Camera device HAL 3.3 [ CAMERA_DEVICE_API_VERSION_3_3 ] + * + * This is the current recommended version of the camera device HAL. + * + * Supports the android.hardware.Camera API, and as of v3.2, the + * android.hardware.camera2 API in LIMITED or FULL modes. + * + * Camera devices that support this version of the HAL must return + * CAMERA_DEVICE_API_VERSION_3_3 in camera_device_t.common.version and in + * camera_info_t.device_version (from camera_module_t.get_camera_info). + * + * CAMERA_DEVICE_API_VERSION_3_3: + * Camera modules that may contain version 3.3 devices must implement at + * least version 2.2 of the camera module interface (as defined by + * camera_module_t.common.module_api_version). + * + * CAMERA_DEVICE_API_VERSION_3_2: + * Camera modules that may contain version 3.2 devices must implement at + * least version 2.2 of the camera module interface (as defined by + * camera_module_t.common.module_api_version). + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * Camera modules that may contain version 3.1 (or 3.0) devices must + * implement at least version 2.0 of the camera module interface + * (as defined by camera_module_t.common.module_api_version). + * + * See camera_common.h for more versioning details. + * + * Documentation index: + * S1. Version history + * S2. Startup and operation sequencing + * S3. Operational modes + * S4. 3A modes and state machines + * S5. Cropping + * S6. Error management + * S7. Key Performance Indicator (KPI) glossary + * S8. Sample Use Cases + * S9. Notes on Controls and Metadata + * S10. Reprocessing flow and controls + */ + +/** + * S1. Version history: + * + * 1.0: Initial Android camera HAL (Android 4.0) [camera.h]: + * + * - Converted from C++ CameraHardwareInterface abstraction layer. + * + * - Supports android.hardware.Camera API. + * + * 2.0: Initial release of expanded-capability HAL (Android 4.2) [camera2.h]: + * + * - Sufficient for implementing existing android.hardware.Camera API. + * + * - Allows for ZSL queue in camera service layer + * + * - Not tested for any new features such manual capture control, Bayer RAW + * capture, reprocessing of RAW data. + * + * 3.0: First revision of expanded-capability HAL: + * + * - Major version change since the ABI is completely different. No change to + * the required hardware capabilities or operational model from 2.0. + * + * - Reworked input request and stream queue interfaces: Framework calls into + * HAL with next request and stream buffers already dequeued. Sync framework + * support is included, necessary for efficient implementations. + * + * - Moved triggers into requests, most notifications into results. + * + * - Consolidated all callbacks into framework into one structure, and all + * setup methods into a single initialize() call. + * + * - Made stream configuration into a single call to simplify stream + * management. Bidirectional streams replace STREAM_FROM_STREAM construct. + * + * - Limited mode semantics for older/limited hardware devices. + * + * 3.1: Minor revision of expanded-capability HAL: + * + * - configure_streams passes consumer usage flags to the HAL. + * + * - flush call to drop all in-flight requests/buffers as fast as possible. + * + * 3.2: Minor revision of expanded-capability HAL: + * + * - Deprecates get_metadata_vendor_tag_ops. Please use get_vendor_tag_ops + * in camera_common.h instead. + * + * - register_stream_buffers deprecated. All gralloc buffers provided + * by framework to HAL in process_capture_request may be new at any time. + * + * - add partial result support. process_capture_result may be called + * multiple times with a subset of the available result before the full + * result is available. + * + * - add manual template to camera3_request_template. The applications may + * use this template to control the capture settings directly. + * + * - Rework the bidirectional and input stream specifications. + * + * - change the input buffer return path. The buffer is returned in + * process_capture_result instead of process_capture_request. + * + * 3.3: Minor revision of expanded-capability HAL: + * + * - OPAQUE and YUV reprocessing API updates. + * + * - Basic support for depth output buffers. + * + * - Addition of data_space field to camera3_stream_t. + * + * - Addition of rotation field to camera3_stream_t. + * + * - Addition of camera3 stream configuration operation mode to camera3_stream_configuration_t + * + */ + +/** + * S2. Startup and general expected operation sequence: + * + * 1. Framework calls camera_module_t->common.open(), which returns a + * hardware_device_t structure. + * + * 2. Framework inspects the hardware_device_t->version field, and instantiates + * the appropriate handler for that version of the camera hardware device. In + * case the version is CAMERA_DEVICE_API_VERSION_3_0, the device is cast to + * a camera3_device_t. + * + * 3. Framework calls camera3_device_t->ops->initialize() with the framework + * callback function pointers. This will only be called this one time after + * open(), before any other functions in the ops structure are called. + * + * 4. The framework calls camera3_device_t->ops->configure_streams() with a list + * of input/output streams to the HAL device. + * + * 5. <= CAMERA_DEVICE_API_VERSION_3_1: + * + * The framework allocates gralloc buffers and calls + * camera3_device_t->ops->register_stream_buffers() for at least one of the + * output streams listed in configure_streams. The same stream is registered + * only once. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * camera3_device_t->ops->register_stream_buffers() is not called and must + * be NULL. + * + * 6. The framework requests default settings for some number of use cases with + * calls to camera3_device_t->ops->construct_default_request_settings(). This + * may occur any time after step 3. + * + * 7. The framework constructs and sends the first capture request to the HAL, + * with settings based on one of the sets of default settings, and with at + * least one output stream, which has been registered earlier by the + * framework. This is sent to the HAL with + * camera3_device_t->ops->process_capture_request(). The HAL must block the + * return of this call until it is ready for the next request to be sent. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The buffer_handle_t provided in the camera3_stream_buffer_t array + * in the camera3_capture_request_t may be new and never-before-seen + * by the HAL on any given new request. + * + * 8. The framework continues to submit requests, and call + * construct_default_request_settings to get default settings buffers for + * other use cases. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * The framework may call register_stream_buffers() at this time for + * not-yet-registered streams. + * + * 9. When the capture of a request begins (sensor starts exposing for the + * capture) or processing a reprocess request begins, the HAL + * calls camera3_callback_ops_t->notify() with the SHUTTER event, including + * the frame number and the timestamp for start of exposure. For a reprocess + * request, the timestamp must be the start of exposure of the input image + * which can be looked up with android.sensor.timestamp from + * camera3_capture_request_t.settings when process_capture_request() is + * called. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * This notify call must be made before the first call to + * process_capture_result() for that frame number. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The camera3_callback_ops_t->notify() call with the SHUTTER event should + * be made as early as possible since the framework will be unable to + * deliver gralloc buffers to the application layer (for that frame) until + * it has a valid timestamp for the start of exposure (or the input image's + * start of exposure for a reprocess request). + * + * Both partial metadata results and the gralloc buffers may be sent to the + * framework at any time before or after the SHUTTER event. + * + * 10. After some pipeline delay, the HAL begins to return completed captures to + * the framework with camera3_callback_ops_t->process_capture_result(). These + * are returned in the same order as the requests were submitted. Multiple + * requests can be in flight at once, depending on the pipeline depth of the + * camera HAL device. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Once a buffer is returned by process_capture_result as part of the + * camera3_stream_buffer_t array, and the fence specified by release_fence + * has been signaled (this is a no-op for -1 fences), the ownership of that + * buffer is considered to be transferred back to the framework. After that, + * the HAL must no longer retain that particular buffer, and the + * framework may clean up the memory for it immediately. + * + * process_capture_result may be called multiple times for a single frame, + * each time with a new disjoint piece of metadata and/or set of gralloc + * buffers. The framework will accumulate these partial metadata results + * into one result. + * + * In particular, it is legal for a process_capture_result to be called + * simultaneously for both a frame N and a frame N+1 as long as the + * above rule holds for gralloc buffers (both input and output). + * + * 11. After some time, the framework may stop submitting new requests, wait for + * the existing captures to complete (all buffers filled, all results + * returned), and then call configure_streams() again. This resets the camera + * hardware and pipeline for a new set of input/output streams. Some streams + * may be reused from the previous configuration; if these streams' buffers + * had already been registered with the HAL, they will not be registered + * again. The framework then continues from step 7, if at least one + * registered output stream remains (otherwise, step 5 is required first). + * + * 12. Alternatively, the framework may call camera3_device_t->common->close() + * to end the camera session. This may be called at any time when no other + * calls from the framework are active, although the call may block until all + * in-flight captures have completed (all results returned, all buffers + * filled). After the close call returns, no more calls to the + * camera3_callback_ops_t functions are allowed from the HAL. Once the + * close() call is underway, the framework may not call any other HAL device + * functions. + * + * 13. In case of an error or other asynchronous event, the HAL must call + * camera3_callback_ops_t->notify() with the appropriate error/event + * message. After returning from a fatal device-wide error notification, the + * HAL should act as if close() had been called on it. However, the HAL must + * either cancel or complete all outstanding captures before calling + * notify(), so that once notify() is called with a fatal error, the + * framework will not receive further callbacks from the device. Methods + * besides close() should return -ENODEV or NULL after the notify() method + * returns from a fatal error message. + */ + +/** + * S3. Operational modes: + * + * The camera 3 HAL device can implement one of two possible operational modes; + * limited and full. Full support is expected from new higher-end + * devices. Limited mode has hardware requirements roughly in line with those + * for a camera HAL device v1 implementation, and is expected from older or + * inexpensive devices. Full is a strict superset of limited, and they share the + * same essential operational flow, as documented above. + * + * The HAL must indicate its level of support with the + * android.info.supportedHardwareLevel static metadata entry, with 0 indicating + * limited mode, and 1 indicating full mode support. + * + * Roughly speaking, limited-mode devices do not allow for application control + * of capture settings (3A control only), high-rate capture of high-resolution + * images, raw sensor readout, or support for YUV output streams above maximum + * recording resolution (JPEG only for large images). + * + * ** Details of limited mode behavior: + * + * - Limited-mode devices do not need to implement accurate synchronization + * between capture request settings and the actual image data + * captured. Instead, changes to settings may take effect some time in the + * future, and possibly not for the same output frame for each settings + * entry. Rapid changes in settings may result in some settings never being + * used for a capture. However, captures that include high-resolution output + * buffers ( > 1080p ) have to use the settings as specified (but see below + * for processing rate). + * + * - Limited-mode devices do not need to support most of the + * settings/result/static info metadata. Specifically, only the following settings + * are expected to be consumed or produced by a limited-mode HAL device: + * + * android.control.aeAntibandingMode (controls and dynamic) + * android.control.aeExposureCompensation (controls and dynamic) + * android.control.aeLock (controls and dynamic) + * android.control.aeMode (controls and dynamic) + * android.control.aeRegions (controls and dynamic) + * android.control.aeTargetFpsRange (controls and dynamic) + * android.control.aePrecaptureTrigger (controls and dynamic) + * android.control.afMode (controls and dynamic) + * android.control.afRegions (controls and dynamic) + * android.control.awbLock (controls and dynamic) + * android.control.awbMode (controls and dynamic) + * android.control.awbRegions (controls and dynamic) + * android.control.captureIntent (controls and dynamic) + * android.control.effectMode (controls and dynamic) + * android.control.mode (controls and dynamic) + * android.control.sceneMode (controls and dynamic) + * android.control.videoStabilizationMode (controls and dynamic) + * android.control.aeAvailableAntibandingModes (static) + * android.control.aeAvailableModes (static) + * android.control.aeAvailableTargetFpsRanges (static) + * android.control.aeCompensationRange (static) + * android.control.aeCompensationStep (static) + * android.control.afAvailableModes (static) + * android.control.availableEffects (static) + * android.control.availableSceneModes (static) + * android.control.availableVideoStabilizationModes (static) + * android.control.awbAvailableModes (static) + * android.control.maxRegions (static) + * android.control.sceneModeOverrides (static) + * android.control.aeState (dynamic) + * android.control.afState (dynamic) + * android.control.awbState (dynamic) + * + * android.flash.mode (controls and dynamic) + * android.flash.info.available (static) + * + * android.info.supportedHardwareLevel (static) + * + * android.jpeg.gpsCoordinates (controls and dynamic) + * android.jpeg.gpsProcessingMethod (controls and dynamic) + * android.jpeg.gpsTimestamp (controls and dynamic) + * android.jpeg.orientation (controls and dynamic) + * android.jpeg.quality (controls and dynamic) + * android.jpeg.thumbnailQuality (controls and dynamic) + * android.jpeg.thumbnailSize (controls and dynamic) + * android.jpeg.availableThumbnailSizes (static) + * android.jpeg.maxSize (static) + * + * android.lens.info.minimumFocusDistance (static) + * + * android.request.id (controls and dynamic) + * + * android.scaler.cropRegion (controls and dynamic) + * android.scaler.availableStreamConfigurations (static) + * android.scaler.availableMinFrameDurations (static) + * android.scaler.availableStallDurations (static) + * android.scaler.availableMaxDigitalZoom (static) + * android.scaler.maxDigitalZoom (static) + * android.scaler.croppingType (static) + * + * android.sensor.orientation (static) + * android.sensor.timestamp (dynamic) + * + * android.statistics.faceDetectMode (controls and dynamic) + * android.statistics.info.availableFaceDetectModes (static) + * android.statistics.faceIds (dynamic) + * android.statistics.faceLandmarks (dynamic) + * android.statistics.faceRectangles (dynamic) + * android.statistics.faceScores (dynamic) + * + * android.sync.frameNumber (dynamic) + * android.sync.maxLatency (static) + * + * - Captures in limited mode that include high-resolution (> 1080p) output + * buffers may block in process_capture_request() until all the output buffers + * have been filled. A full-mode HAL device must process sequences of + * high-resolution requests at the rate indicated in the static metadata for + * that pixel format. The HAL must still call process_capture_result() to + * provide the output; the framework must simply be prepared for + * process_capture_request() to block until after process_capture_result() for + * that request completes for high-resolution captures for limited-mode + * devices. + * + * - Full-mode devices must support below additional capabilities: + * - 30fps at maximum resolution is preferred, more than 20fps is required. + * - Per frame control (android.sync.maxLatency == PER_FRAME_CONTROL). + * - Sensor manual control metadata. See MANUAL_SENSOR defined in + * android.request.availableCapabilities. + * - Post-processing manual control metadata. See MANUAL_POST_PROCESSING defined + * in android.request.availableCapabilities. + * + */ + +/** + * S4. 3A modes and state machines: + * + * While the actual 3A algorithms are up to the HAL implementation, a high-level + * state machine description is defined by the HAL interface, to allow the HAL + * device and the framework to communicate about the current state of 3A, and to + * trigger 3A events. + * + * When the device is opened, all the individual 3A states must be + * STATE_INACTIVE. Stream configuration does not reset 3A. For example, locked + * focus must be maintained across the configure() call. + * + * Triggering a 3A action involves simply setting the relevant trigger entry in + * the settings for the next request to indicate start of trigger. For example, + * the trigger for starting an autofocus scan is setting the entry + * ANDROID_CONTROL_AF_TRIGGER to ANDROID_CONTROL_AF_TRIGGER_START for one + * request, and cancelling an autofocus scan is triggered by setting + * ANDROID_CONTROL_AF_TRIGGER to ANDROID_CONTRL_AF_TRIGGER_CANCEL. Otherwise, + * the entry will not exist, or be set to ANDROID_CONTROL_AF_TRIGGER_IDLE. Each + * request with a trigger entry set to a non-IDLE value will be treated as an + * independent triggering event. + * + * At the top level, 3A is controlled by the ANDROID_CONTROL_MODE setting, which + * selects between no 3A (ANDROID_CONTROL_MODE_OFF), normal AUTO mode + * (ANDROID_CONTROL_MODE_AUTO), and using the scene mode setting + * (ANDROID_CONTROL_USE_SCENE_MODE). + * + * - In OFF mode, each of the individual AE/AF/AWB modes are effectively OFF, + * and none of the capture controls may be overridden by the 3A routines. + * + * - In AUTO mode, Auto-focus, auto-exposure, and auto-whitebalance all run + * their own independent algorithms, and have their own mode, state, and + * trigger metadata entries, as listed in the next section. + * + * - In USE_SCENE_MODE, the value of the ANDROID_CONTROL_SCENE_MODE entry must + * be used to determine the behavior of 3A routines. In SCENE_MODEs other than + * FACE_PRIORITY, the HAL must override the values of + * ANDROId_CONTROL_AE/AWB/AF_MODE to be the mode it prefers for the selected + * SCENE_MODE. For example, the HAL may prefer SCENE_MODE_NIGHT to use + * CONTINUOUS_FOCUS AF mode. Any user selection of AE/AWB/AF_MODE when scene + * must be ignored for these scene modes. + * + * - For SCENE_MODE_FACE_PRIORITY, the AE/AWB/AF_MODE controls work as in + * ANDROID_CONTROL_MODE_AUTO, but the 3A routines must bias toward metering + * and focusing on any detected faces in the scene. + * + * S4.1. Auto-focus settings and result entries: + * + * Main metadata entries: + * + * ANDROID_CONTROL_AF_MODE: Control for selecting the current autofocus + * mode. Set by the framework in the request settings. + * + * AF_MODE_OFF: AF is disabled; the framework/app directly controls lens + * position. + * + * AF_MODE_AUTO: Single-sweep autofocus. No lens movement unless AF is + * triggered. + * + * AF_MODE_MACRO: Single-sweep up-close autofocus. No lens movement unless + * AF is triggered. + * + * AF_MODE_CONTINUOUS_VIDEO: Smooth continuous focusing, for recording + * video. Triggering immediately locks focus in current + * position. Canceling resumes cotinuous focusing. + * + * AF_MODE_CONTINUOUS_PICTURE: Fast continuous focusing, for + * zero-shutter-lag still capture. Triggering locks focus once currently + * active sweep concludes. Canceling resumes continuous focusing. + * + * AF_MODE_EDOF: Advanced extended depth of field focusing. There is no + * autofocus scan, so triggering one or canceling one has no effect. + * Images are focused automatically by the HAL. + * + * ANDROID_CONTROL_AF_STATE: Dynamic metadata describing the current AF + * algorithm state, reported by the HAL in the result metadata. + * + * AF_STATE_INACTIVE: No focusing has been done, or algorithm was + * reset. Lens is not moving. Always the state for MODE_OFF or MODE_EDOF. + * When the device is opened, it must start in this state. + * + * AF_STATE_PASSIVE_SCAN: A continuous focus algorithm is currently scanning + * for good focus. The lens is moving. + * + * AF_STATE_PASSIVE_FOCUSED: A continuous focus algorithm believes it is + * well focused. The lens is not moving. The HAL may spontaneously leave + * this state. + * + * AF_STATE_PASSIVE_UNFOCUSED: A continuous focus algorithm believes it is + * not well focused. The lens is not moving. The HAL may spontaneously + * leave this state. + * + * AF_STATE_ACTIVE_SCAN: A scan triggered by the user is underway. + * + * AF_STATE_FOCUSED_LOCKED: The AF algorithm believes it is focused. The + * lens is not moving. + * + * AF_STATE_NOT_FOCUSED_LOCKED: The AF algorithm has been unable to + * focus. The lens is not moving. + * + * ANDROID_CONTROL_AF_TRIGGER: Control for starting an autofocus scan, the + * meaning of which is mode- and state- dependent. Set by the framework in + * the request settings. + * + * AF_TRIGGER_IDLE: No current trigger. + * + * AF_TRIGGER_START: Trigger start of AF scan. Effect is mode and state + * dependent. + * + * AF_TRIGGER_CANCEL: Cancel current AF scan if any, and reset algorithm to + * default. + * + * Additional metadata entries: + * + * ANDROID_CONTROL_AF_REGIONS: Control for selecting the regions of the FOV + * that should be used to determine good focus. This applies to all AF + * modes that scan for focus. Set by the framework in the request + * settings. + * + * S4.2. Auto-exposure settings and result entries: + * + * Main metadata entries: + * + * ANDROID_CONTROL_AE_MODE: Control for selecting the current auto-exposure + * mode. Set by the framework in the request settings. + * + * AE_MODE_OFF: Autoexposure is disabled; the user controls exposure, gain, + * frame duration, and flash. + * + * AE_MODE_ON: Standard autoexposure, with flash control disabled. User may + * set flash to fire or to torch mode. + * + * AE_MODE_ON_AUTO_FLASH: Standard autoexposure, with flash on at HAL's + * discretion for precapture and still capture. User control of flash + * disabled. + * + * AE_MODE_ON_ALWAYS_FLASH: Standard autoexposure, with flash always fired + * for capture, and at HAL's discretion for precapture.. User control of + * flash disabled. + * + * AE_MODE_ON_AUTO_FLASH_REDEYE: Standard autoexposure, with flash on at + * HAL's discretion for precapture and still capture. Use a flash burst + * at end of precapture sequence to reduce redeye in the final + * picture. User control of flash disabled. + * + * ANDROID_CONTROL_AE_STATE: Dynamic metadata describing the current AE + * algorithm state, reported by the HAL in the result metadata. + * + * AE_STATE_INACTIVE: Initial AE state after mode switch. When the device is + * opened, it must start in this state. + * + * AE_STATE_SEARCHING: AE is not converged to a good value, and is adjusting + * exposure parameters. + * + * AE_STATE_CONVERGED: AE has found good exposure values for the current + * scene, and the exposure parameters are not changing. HAL may + * spontaneously leave this state to search for better solution. + * + * AE_STATE_LOCKED: AE has been locked with the AE_LOCK control. Exposure + * values are not changing. + * + * AE_STATE_FLASH_REQUIRED: The HAL has converged exposure, but believes + * flash is required for a sufficiently bright picture. Used for + * determining if a zero-shutter-lag frame can be used. + * + * AE_STATE_PRECAPTURE: The HAL is in the middle of a precapture + * sequence. Depending on AE mode, this mode may involve firing the + * flash for metering, or a burst of flash pulses for redeye reduction. + * + * ANDROID_CONTROL_AE_PRECAPTURE_TRIGGER: Control for starting a metering + * sequence before capturing a high-quality image. Set by the framework in + * the request settings. + * + * PRECAPTURE_TRIGGER_IDLE: No current trigger. + * + * PRECAPTURE_TRIGGER_START: Start a precapture sequence. The HAL should + * use the subsequent requests to measure good exposure/white balance + * for an upcoming high-resolution capture. + * + * Additional metadata entries: + * + * ANDROID_CONTROL_AE_LOCK: Control for locking AE controls to their current + * values + * + * ANDROID_CONTROL_AE_EXPOSURE_COMPENSATION: Control for adjusting AE + * algorithm target brightness point. + * + * ANDROID_CONTROL_AE_TARGET_FPS_RANGE: Control for selecting the target frame + * rate range for the AE algorithm. The AE routine cannot change the frame + * rate to be outside these bounds. + * + * ANDROID_CONTROL_AE_REGIONS: Control for selecting the regions of the FOV + * that should be used to determine good exposure levels. This applies to + * all AE modes besides OFF. + * + * S4.3. Auto-whitebalance settings and result entries: + * + * Main metadata entries: + * + * ANDROID_CONTROL_AWB_MODE: Control for selecting the current white-balance + * mode. + * + * AWB_MODE_OFF: Auto-whitebalance is disabled. User controls color matrix. + * + * AWB_MODE_AUTO: Automatic white balance is enabled; 3A controls color + * transform, possibly using more complex transforms than a simple + * matrix. + * + * AWB_MODE_INCANDESCENT: Fixed white balance settings good for indoor + * incandescent (tungsten) lighting, roughly 2700K. + * + * AWB_MODE_FLUORESCENT: Fixed white balance settings good for fluorescent + * lighting, roughly 5000K. + * + * AWB_MODE_WARM_FLUORESCENT: Fixed white balance settings good for + * fluorescent lighting, roughly 3000K. + * + * AWB_MODE_DAYLIGHT: Fixed white balance settings good for daylight, + * roughly 5500K. + * + * AWB_MODE_CLOUDY_DAYLIGHT: Fixed white balance settings good for clouded + * daylight, roughly 6500K. + * + * AWB_MODE_TWILIGHT: Fixed white balance settings good for + * near-sunset/sunrise, roughly 15000K. + * + * AWB_MODE_SHADE: Fixed white balance settings good for areas indirectly + * lit by the sun, roughly 7500K. + * + * ANDROID_CONTROL_AWB_STATE: Dynamic metadata describing the current AWB + * algorithm state, reported by the HAL in the result metadata. + * + * AWB_STATE_INACTIVE: Initial AWB state after mode switch. When the device + * is opened, it must start in this state. + * + * AWB_STATE_SEARCHING: AWB is not converged to a good value, and is + * changing color adjustment parameters. + * + * AWB_STATE_CONVERGED: AWB has found good color adjustment values for the + * current scene, and the parameters are not changing. HAL may + * spontaneously leave this state to search for better solution. + * + * AWB_STATE_LOCKED: AWB has been locked with the AWB_LOCK control. Color + * adjustment values are not changing. + * + * Additional metadata entries: + * + * ANDROID_CONTROL_AWB_LOCK: Control for locking AWB color adjustments to + * their current values. + * + * ANDROID_CONTROL_AWB_REGIONS: Control for selecting the regions of the FOV + * that should be used to determine good color balance. This applies only + * to auto-WB mode. + * + * S4.4. General state machine transition notes + * + * Switching between AF, AE, or AWB modes always resets the algorithm's state + * to INACTIVE. Similarly, switching between CONTROL_MODE or + * CONTROL_SCENE_MODE if CONTROL_MODE == USE_SCENE_MODE resets all the + * algorithm states to INACTIVE. + * + * The tables below are per-mode. + * + * S4.5. AF state machines + * + * when enabling AF or changing AF mode + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| Any | AF mode change| INACTIVE | | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AF_MODE_OFF or AF_MODE_EDOF + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | | INACTIVE | Never changes | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AF_MODE_AUTO or AF_MODE_MACRO + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | AF_TRIGGER | ACTIVE_SCAN | Start AF sweep | + *| | | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| ACTIVE_SCAN | AF sweep done | FOCUSED_LOCKED | If AF successful | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| ACTIVE_SCAN | AF sweep done | NOT_FOCUSED_LOCKED | If AF successful | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| ACTIVE_SCAN | AF_CANCEL | INACTIVE | Cancel/reset AF | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Cancel/reset AF | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_TRIGGER | ACTIVE_SCAN | Start new sweep | + *| | | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Cancel/reset AF | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_TRIGGER | ACTIVE_SCAN | Start new sweep | + *| | | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| All states | mode change | INACTIVE | | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AF_MODE_CONTINUOUS_VIDEO + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | AF_TRIGGER | NOT_FOCUSED_LOCKED | AF state query | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | HAL completes | PASSIVE_FOCUSED | End AF scan | + *| | current scan | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | HAL fails | PASSIVE_UNFOCUSED | End AF scan | + *| | current scan | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_TRIGGER | FOCUSED_LOCKED | Immediate trans. | + *| | | | if focus is good | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_TRIGGER | NOT_FOCUSED_LOCKED | Immediate trans. | + *| | | | if focus is bad | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_CANCEL | INACTIVE | Reset lens | + *| | | | position | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_FOCUSED | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_UNFOCUSED | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_FOCUSED | AF_TRIGGER | FOCUSED_LOCKED | Immediate trans. | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_UNFOCUSED | AF_TRIGGER | NOT_FOCUSED_LOCKED | Immediate trans. | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_TRIGGER | FOCUSED_LOCKED | No effect | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Restart AF scan | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_TRIGGER | NOT_FOCUSED_LOCKED | No effect | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Restart AF scan | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AF_MODE_CONTINUOUS_PICTURE + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | AF_TRIGGER | NOT_FOCUSED_LOCKED | AF state query | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | HAL completes | PASSIVE_FOCUSED | End AF scan | + *| | current scan | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | HAL fails | PASSIVE_UNFOCUSED | End AF scan | + *| | current scan | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_TRIGGER | FOCUSED_LOCKED | Eventual trans. | + *| | | | once focus good | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_TRIGGER | NOT_FOCUSED_LOCKED | Eventual trans. | + *| | | | if cannot focus | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_SCAN | AF_CANCEL | INACTIVE | Reset lens | + *| | | | position | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_FOCUSED | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_UNFOCUSED | HAL initiates | PASSIVE_SCAN | Start AF scan | + *| | new scan | | Lens now moving | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_FOCUSED | AF_TRIGGER | FOCUSED_LOCKED | Immediate trans. | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| PASSIVE_UNFOCUSED | AF_TRIGGER | NOT_FOCUSED_LOCKED | Immediate trans. | + *| | | | Lens now locked | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_TRIGGER | FOCUSED_LOCKED | No effect | + *+--------------------+---------------+--------------------+------------------+ + *| FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Restart AF scan | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_TRIGGER | NOT_FOCUSED_LOCKED | No effect | + *+--------------------+---------------+--------------------+------------------+ + *| NOT_FOCUSED_LOCKED | AF_CANCEL | INACTIVE | Restart AF scan | + *+--------------------+---------------+--------------------+------------------+ + * + * S4.6. AE and AWB state machines + * + * The AE and AWB state machines are mostly identical. AE has additional + * FLASH_REQUIRED and PRECAPTURE states. So rows below that refer to those two + * states should be ignored for the AWB state machine. + * + * when enabling AE/AWB or changing AE/AWB mode + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| Any | mode change | INACTIVE | | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AE_MODE_OFF / AWB mode not AUTO + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | | INACTIVE | AE/AWB disabled | + *+--------------------+---------------+--------------------+------------------+ + * + * mode = AE_MODE_ON_* / AWB_MODE_AUTO + *| state | trans. cause | new state | notes | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | HAL initiates | SEARCHING | | + *| | AE/AWB scan | | | + *+--------------------+---------------+--------------------+------------------+ + *| INACTIVE | AE/AWB_LOCK | LOCKED | values locked | + *| | on | | | + *+--------------------+---------------+--------------------+------------------+ + *| SEARCHING | HAL finishes | CONVERGED | good values, not | + *| | AE/AWB scan | | changing | + *+--------------------+---------------+--------------------+------------------+ + *| SEARCHING | HAL finishes | FLASH_REQUIRED | converged but too| + *| | AE scan | | dark w/o flash | + *+--------------------+---------------+--------------------+------------------+ + *| SEARCHING | AE/AWB_LOCK | LOCKED | values locked | + *| | on | | | + *+--------------------+---------------+--------------------+------------------+ + *| CONVERGED | HAL initiates | SEARCHING | values locked | + *| | AE/AWB scan | | | + *+--------------------+---------------+--------------------+------------------+ + *| CONVERGED | AE/AWB_LOCK | LOCKED | values locked | + *| | on | | | + *+--------------------+---------------+--------------------+------------------+ + *| FLASH_REQUIRED | HAL initiates | SEARCHING | values locked | + *| | AE/AWB scan | | | + *+--------------------+---------------+--------------------+------------------+ + *| FLASH_REQUIRED | AE/AWB_LOCK | LOCKED | values locked | + *| | on | | | + *+--------------------+---------------+--------------------+------------------+ + *| LOCKED | AE/AWB_LOCK | SEARCHING | values not good | + *| | off | | after unlock | + *+--------------------+---------------+--------------------+------------------+ + *| LOCKED | AE/AWB_LOCK | CONVERGED | values good | + *| | off | | after unlock | + *+--------------------+---------------+--------------------+------------------+ + *| LOCKED | AE_LOCK | FLASH_REQUIRED | exposure good, | + *| | off | | but too dark | + *+--------------------+---------------+--------------------+------------------+ + *| All AE states | PRECAPTURE_ | PRECAPTURE | Start precapture | + *| | START | | sequence | + *+--------------------+---------------+--------------------+------------------+ + *| PRECAPTURE | Sequence done.| CONVERGED | Ready for high- | + *| | AE_LOCK off | | quality capture | + *+--------------------+---------------+--------------------+------------------+ + *| PRECAPTURE | Sequence done.| LOCKED | Ready for high- | + *| | AE_LOCK on | | quality capture | + *+--------------------+---------------+--------------------+------------------+ + * + */ + +/** + * S5. Cropping: + * + * Cropping of the full pixel array (for digital zoom and other use cases where + * a smaller FOV is desirable) is communicated through the + * ANDROID_SCALER_CROP_REGION setting. This is a per-request setting, and can + * change on a per-request basis, which is critical for implementing smooth + * digital zoom. + * + * The region is defined as a rectangle (x, y, width, height), with (x, y) + * describing the top-left corner of the rectangle. The rectangle is defined on + * the coordinate system of the sensor active pixel array, with (0,0) being the + * top-left pixel of the active pixel array. Therefore, the width and height + * cannot be larger than the dimensions reported in the + * ANDROID_SENSOR_ACTIVE_PIXEL_ARRAY static info field. The minimum allowed + * width and height are reported by the HAL through the + * ANDROID_SCALER_MAX_DIGITAL_ZOOM static info field, which describes the + * maximum supported zoom factor. Therefore, the minimum crop region width and + * height are: + * + * {width, height} = + * { floor(ANDROID_SENSOR_ACTIVE_PIXEL_ARRAY[0] / + * ANDROID_SCALER_MAX_DIGITAL_ZOOM), + * floor(ANDROID_SENSOR_ACTIVE_PIXEL_ARRAY[1] / + * ANDROID_SCALER_MAX_DIGITAL_ZOOM) } + * + * If the crop region needs to fulfill specific requirements (for example, it + * needs to start on even coordinates, and its width/height needs to be even), + * the HAL must do the necessary rounding and write out the final crop region + * used in the output result metadata. Similarly, if the HAL implements video + * stabilization, it must adjust the result crop region to describe the region + * actually included in the output after video stabilization is applied. In + * general, a camera-using application must be able to determine the field of + * view it is receiving based on the crop region, the dimensions of the image + * sensor, and the lens focal length. + * + * It is assumed that the cropping is applied after raw to other color space + * conversion. Raw streams (RAW16 and RAW_OPAQUE) don't have this conversion stage, + * and are not croppable. Therefore, the crop region must be ignored by the HAL + * for raw streams. + * + * Since the crop region applies to all non-raw streams, which may have different aspect + * ratios than the crop region, the exact sensor region used for each stream may + * be smaller than the crop region. Specifically, each stream should maintain + * square pixels and its aspect ratio by minimally further cropping the defined + * crop region. If the stream's aspect ratio is wider than the crop region, the + * stream should be further cropped vertically, and if the stream's aspect ratio + * is narrower than the crop region, the stream should be further cropped + * horizontally. + * + * In all cases, the stream crop must be centered within the full crop region, + * and each stream is only either cropped horizontally or vertical relative to + * the full crop region, never both. + * + * For example, if two streams are defined, a 640x480 stream (4:3 aspect), and a + * 1280x720 stream (16:9 aspect), below demonstrates the expected output regions + * for each stream for a few sample crop regions, on a hypothetical 3 MP (2000 x + * 1500 pixel array) sensor. + * + * Crop region: (500, 375, 1000, 750) (4:3 aspect ratio) + * + * 640x480 stream crop: (500, 375, 1000, 750) (equal to crop region) + * 1280x720 stream crop: (500, 469, 1000, 562) (marked with =) + * + * 0 1000 2000 + * +---------+---------+---------+----------+ + * | Active pixel array | + * | | + * | | + * + +-------------------+ + 375 + * | | | | + * | O===================O | + * | I 1280x720 stream I | + * + I I + 750 + * | I I | + * | O===================O | + * | | | | + * + +-------------------+ + 1125 + * | Crop region, 640x480 stream | + * | | + * | | + * +---------+---------+---------+----------+ 1500 + * + * Crop region: (500, 375, 1333, 750) (16:9 aspect ratio) + * + * 640x480 stream crop: (666, 375, 1000, 750) (marked with =) + * 1280x720 stream crop: (500, 375, 1333, 750) (equal to crop region) + * + * 0 1000 2000 + * +---------+---------+---------+----------+ + * | Active pixel array | + * | | + * | | + * + +---O==================O---+ + 375 + * | | I 640x480 stream I | | + * | | I I | | + * | | I I | | + * + | I I | + 750 + * | | I I | | + * | | I I | | + * | | I I | | + * + +---O==================O---+ + 1125 + * | Crop region, 1280x720 stream | + * | | + * | | + * +---------+---------+---------+----------+ 1500 + * + * Crop region: (500, 375, 750, 750) (1:1 aspect ratio) + * + * 640x480 stream crop: (500, 469, 750, 562) (marked with =) + * 1280x720 stream crop: (500, 543, 750, 414) (marged with #) + * + * 0 1000 2000 + * +---------+---------+---------+----------+ + * | Active pixel array | + * | | + * | | + * + +--------------+ + 375 + * | O==============O | + * | ################ | + * | # # | + * + # # + 750 + * | # # | + * | ################ 1280x720 | + * | O==============O 640x480 | + * + +--------------+ + 1125 + * | Crop region | + * | | + * | | + * +---------+---------+---------+----------+ 1500 + * + * And a final example, a 1024x1024 square aspect ratio stream instead of the + * 480p stream: + * + * Crop region: (500, 375, 1000, 750) (4:3 aspect ratio) + * + * 1024x1024 stream crop: (625, 375, 750, 750) (marked with #) + * 1280x720 stream crop: (500, 469, 1000, 562) (marked with =) + * + * 0 1000 2000 + * +---------+---------+---------+----------+ + * | Active pixel array | + * | | + * | 1024x1024 stream | + * + +--###############--+ + 375 + * | | # # | | + * | O===================O | + * | I 1280x720 stream I | + * + I I + 750 + * | I I | + * | O===================O | + * | | # # | | + * + +--###############--+ + 1125 + * | Crop region | + * | | + * | | + * +---------+---------+---------+----------+ 1500 + * + */ + +/** + * S6. Error management: + * + * Camera HAL device ops functions that have a return value will all return + * -ENODEV / NULL in case of a serious error. This means the device cannot + * continue operation, and must be closed by the framework. Once this error is + * returned by some method, or if notify() is called with ERROR_DEVICE, only + * the close() method can be called successfully. All other methods will return + * -ENODEV / NULL. + * + * If a device op is called in the wrong sequence, for example if the framework + * calls configure_streams() is called before initialize(), the device must + * return -ENOSYS from the call, and do nothing. + * + * Transient errors in image capture must be reported through notify() as follows: + * + * - The failure of an entire capture to occur must be reported by the HAL by + * calling notify() with ERROR_REQUEST. Individual errors for the result + * metadata or the output buffers must not be reported in this case. + * + * - If the metadata for a capture cannot be produced, but some image buffers + * were filled, the HAL must call notify() with ERROR_RESULT. + * + * - If an output image buffer could not be filled, but either the metadata was + * produced or some other buffers were filled, the HAL must call notify() with + * ERROR_BUFFER for each failed buffer. + * + * In each of these transient failure cases, the HAL must still call + * process_capture_result, with valid output and input (if an input buffer was + * submitted) buffer_handle_t. If the result metadata could not be produced, it + * should be NULL. If some buffers could not be filled, they must be returned with + * process_capture_result in the error state, their release fences must be set to + * the acquire fences passed by the framework, or -1 if they have been waited on by + * the HAL already. + * + * Invalid input arguments result in -EINVAL from the appropriate methods. In + * that case, the framework must act as if that call had never been made. + * + */ + +/** + * S7. Key Performance Indicator (KPI) glossary: + * + * This includes some critical definitions that are used by KPI metrics. + * + * Pipeline Latency: + * For a given capture request, the duration from the framework calling + * process_capture_request to the HAL sending capture result and all buffers + * back by process_capture_result call. To make the Pipeline Latency measure + * independent of frame rate, it is measured by frame count. + * + * For example, when frame rate is 30 (fps), the frame duration (time interval + * between adjacent frame capture time) is 33 (ms). + * If it takes 5 frames for framework to get the result and buffers back for + * a given request, then the Pipeline Latency is 5 (frames), instead of + * 5 x 33 = 165 (ms). + * + * The Pipeline Latency is determined by android.request.pipelineDepth and + * android.request.pipelineMaxDepth, see their definitions for more details. + * + */ + +/** + * S8. Sample Use Cases: + * + * This includes some typical use case examples the camera HAL may support. + * + * S8.1 Zero Shutter Lag (ZSL) with CAMERA3_STREAM_BIDIRECTIONAL stream. + * + * For this use case, the bidirectional stream will be used by the framework as follows: + * + * 1. The framework includes a buffer from this stream as output buffer in a + * request as normal. + * + * 2. Once the HAL device returns a filled output buffer to the framework, + * the framework may do one of two things with the filled buffer: + * + * 2. a. The framework uses the filled data, and returns the now-used buffer + * to the stream queue for reuse. This behavior exactly matches the + * OUTPUT type of stream. + * + * 2. b. The framework wants to reprocess the filled data, and uses the + * buffer as an input buffer for a request. Once the HAL device has + * used the reprocessing buffer, it then returns it to the + * framework. The framework then returns the now-used buffer to the + * stream queue for reuse. + * + * 3. The HAL device will be given the buffer again as an output buffer for + * a request at some future point. + * + * For ZSL use case, the pixel format for bidirectional stream will be + * HAL_PIXEL_FORMAT_RAW_OPAQUE or HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED if it + * is listed in android.scaler.availableInputOutputFormatsMap. When + * HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED is used, the gralloc + * usage flags for the consumer endpoint will be set to GRALLOC_USAGE_HW_CAMERA_ZSL. + * A configuration stream list that has BIDIRECTIONAL stream used as input, will + * usually also have a distinct OUTPUT stream to get the reprocessing data. For example, + * for the ZSL use case, the stream list might be configured with the following: + * + * - A HAL_PIXEL_FORMAT_RAW_OPAQUE bidirectional stream is used + * as input. + * - And a HAL_PIXEL_FORMAT_BLOB (JPEG) output stream. + * + * S8.2 ZSL (OPAQUE) reprocessing with CAMERA3_STREAM_INPUT stream. + * + * CAMERA_DEVICE_API_VERSION_3_3: + * When OPAQUE_REPROCESSING capability is supported by the camera device, the INPUT stream + * can be used for application/framework implemented use case like Zero Shutter Lag (ZSL). + * This kind of stream will be used by the framework as follows: + * + * 1. Application/framework configures an opaque (RAW or YUV based) format output stream that is + * used to produce the ZSL output buffers. The stream pixel format will be + * HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED. + * + * 2. Application/framework configures an opaque format input stream that is used to + * send the reprocessing ZSL buffers to the HAL. The stream pixel format will + * also be HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED. + * + * 3. Application/framework configures a YUV/JPEG output stream that is used to receive the + * reprocessed data. The stream pixel format will be YCbCr_420/HAL_PIXEL_FORMAT_BLOB. + * + * 4. Application/framework picks a ZSL buffer from the ZSL output stream when a ZSL capture is + * issued by the application, and sends the data back as an input buffer in a + * reprocessing request, then sends to the HAL for reprocessing. + * + * 5. The HAL sends back the output YUV/JPEG result to framework. + * + * The HAL can select the actual opaque buffer format and configure the ISP pipeline + * appropriately based on the HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED format and + * the gralloc usage flag GRALLOC_USAGE_HW_CAMERA_ZSL. + + * S8.3 YUV reprocessing with CAMERA3_STREAM_INPUT stream. + * + * When YUV reprocessing is supported by the HAL, the INPUT stream + * can be used for the YUV reprocessing use cases like lucky-shot and image fusion. + * This kind of stream will be used by the framework as follows: + * + * 1. Application/framework configures an YCbCr_420 format output stream that is + * used to produce the output buffers. + * + * 2. Application/framework configures an YCbCr_420 format input stream that is used to + * send the reprocessing YUV buffers to the HAL. + * + * 3. Application/framework configures a YUV/JPEG output stream that is used to receive the + * reprocessed data. The stream pixel format will be YCbCr_420/HAL_PIXEL_FORMAT_BLOB. + * + * 4. Application/framework processes the output buffers (could be as simple as picking + * an output buffer directly) from the output stream when a capture is issued, and sends + * the data back as an input buffer in a reprocessing request, then sends to the HAL + * for reprocessing. + * + * 5. The HAL sends back the output YUV/JPEG result to framework. + * + */ + +/** + * S9. Notes on Controls and Metadata + * + * This section contains notes about the interpretation and usage of various metadata tags. + * + * S9.1 HIGH_QUALITY and FAST modes. + * + * Many camera post-processing blocks may be listed as having HIGH_QUALITY, + * FAST, and OFF operating modes. These blocks will typically also have an + * 'available modes' tag representing which of these operating modes are + * available on a given device. The general policy regarding implementing + * these modes is as follows: + * + * 1. Operating mode controls of hardware blocks that cannot be disabled + * must not list OFF in their corresponding 'available modes' tags. + * + * 2. OFF will always be included in their corresponding 'available modes' + * tag if it is possible to disable that hardware block. + * + * 3. FAST must always be included in the 'available modes' tags for all + * post-processing blocks supported on the device. If a post-processing + * block also has a slower and higher quality operating mode that does + * not meet the framerate requirements for FAST mode, HIGH_QUALITY should + * be included in the 'available modes' tag to represent this operating + * mode. + */ + +/** + * S10. Reprocessing flow and controls + * + * This section describes the OPAQUE and YUV reprocessing flow and controls. OPAQUE reprocessing + * uses an opaque format that is not directly application-visible, and the application can + * only select some of the output buffers and send back to HAL for reprocessing, while YUV + * reprocessing gives the application opportunity to process the buffers before reprocessing. + * + * S8 gives the stream configurations for the typical reprocessing uses cases, + * this section specifies the buffer flow and controls in more details. + * + * S10.1 OPAQUE (typically for ZSL use case) reprocessing flow and controls + * + * For OPAQUE reprocessing (e.g. ZSL) use case, after the application creates the specific + * output and input streams, runtime buffer flow and controls are specified as below: + * + * 1. Application starts output streaming by sending repeating requests for output + * opaque buffers and preview. The buffers are held by an application + * maintained circular buffer. The requests are based on CAMERA3_TEMPLATE_ZERO_SHUTTER_LAG + * capture template, which should have all necessary settings that guarantee output + * frame rate is not slowed down relative to sensor output frame rate. + * + * 2. When a capture is issued, the application selects one output buffer based + * on application buffer selection logic, e.g. good AE and AF statistics etc. + * Application then creates an reprocess request based on the capture result associated + * with this selected buffer. The selected output buffer is now added to this reprocess + * request as an input buffer, the output buffer of this reprocess request should be + * either JPEG output buffer or YUV output buffer, or both, depending on the application + * choice. + * + * 3. Application then alters the reprocess settings to get best image quality. The HAL must + * support and only support below controls if the HAL support OPAQUE_REPROCESSING capability: + * - android.jpeg.* (if JPEG buffer is included as one of the output) + * - android.noiseReduction.mode (change to HIGH_QUALITY if it is supported) + * - android.edge.mode (change to HIGH_QUALITY if it is supported) + * All other controls must be ignored by the HAL. + * 4. HAL processed the input buffer and return the output buffers in the capture results + * as normal. + * + * S10.2 YUV reprocessing flow and controls + * + * The YUV reprocessing buffer flow is similar as OPAQUE reprocessing, with below difference: + * + * 1. Application may want to have finer granularity control of the intermediate YUV images + * (before reprocessing). For example, application may choose + * - android.noiseReduction.mode == MINIMAL + * to make sure the no YUV domain noise reduction has applied to the output YUV buffers, + * then it can do its own advanced noise reduction on them. For OPAQUE reprocessing case, this + * doesn't matter, as long as the final reprocessed image has the best quality. + * 2. Application may modify the YUV output buffer data. For example, for image fusion use + * case, where multiple output images are merged together to improve the signal-to-noise + * ratio (SNR). The input buffer may be generated from multiple buffers by the application. + * To avoid excessive amount of noise reduction and insufficient amount of edge enhancement + * being applied to the input buffer, the application can hint the HAL how much effective + * exposure time improvement has been done by the application, then the HAL can adjust the + * noise reduction and edge enhancement paramters to get best reprocessed image quality. + * Below tag can be used for this purpose: + * - android.reprocess.effectiveExposureFactor + * The value would be exposure time increase factor applied to the original output image, + * for example, if there are N image merged, the exposure time increase factor would be up + * to sqrt(N). See this tag spec for more details. + * + * S10.3 Reprocessing pipeline characteristics + * + * Reprocessing pipeline has below different characteristics comparing with normal output + * pipeline: + * + * 1. The reprocessing result can be returned ahead of the pending normal output results. But + * the FIFO ordering must be maintained for all reprocessing results. For example, there are + * below requests (A stands for output requests, B stands for reprocessing requests) + * being processed by the HAL: + * A1, A2, A3, A4, B1, A5, B2, A6... + * result of B1 can be returned before A1-A4, but result of B2 must be returned after B1. + * 2. Single input rule: For a given reprocessing request, all output buffers must be from the + * input buffer, rather than sensor output. For example, if a reprocess request include both + * JPEG and preview buffers, all output buffers must be produced from the input buffer + * included by the reprocessing request, rather than sensor. The HAL must not output preview + * buffers from sensor, while output JPEG buffer from the input buffer. + * 3. Input buffer will be from camera output directly (ZSL case) or indirectly(image fusion + * case). For the case where buffer is modified, the size will remain same. The HAL can + * notify CAMERA3_MSG_ERROR_REQUEST if buffer from unknown source is sent. + * 4. Result as reprocessing request: The HAL can expect that a reprocessing request is a copy + * of one of the output results with minor allowed setting changes. The HAL can notify + * CAMERA3_MSG_ERROR_REQUEST if a request from unknown source is issued. + * 5. Output buffers may not be used as inputs across the configure stream boundary, This is + * because an opaque stream like the ZSL output stream may have different actual image size + * inside of the ZSL buffer to save power and bandwidth for smaller resolution JPEG capture. + * The HAL may notify CAMERA3_MSG_ERROR_REQUEST if this case occurs. + * 6. HAL Reprocess requests error reporting during flush should follow the same rule specified + * by flush() method. + * + */ + +__BEGIN_DECLS + +struct camera3_device; + +/********************************************************************** + * + * Camera3 stream and stream buffer definitions. + * + * These structs and enums define the handles and contents of the input and + * output streams connecting the HAL to various framework and application buffer + * consumers. Each stream is backed by a gralloc buffer queue. + * + */ + +/** + * camera3_stream_type_t: + * + * The type of the camera stream, which defines whether the camera HAL device is + * the producer or the consumer for that stream, and how the buffers of the + * stream relate to the other streams. + */ +typedef enum camera3_stream_type { + /** + * This stream is an output stream; the camera HAL device will be + * responsible for filling buffers from this stream with newly captured or + * reprocessed image data. + */ + CAMERA3_STREAM_OUTPUT = 0, + + /** + * This stream is an input stream; the camera HAL device will be responsible + * for reading buffers from this stream and sending them through the camera + * processing pipeline, as if the buffer was a newly captured image from the + * imager. + * + * The pixel format for input stream can be any format reported by + * android.scaler.availableInputOutputFormatsMap. The pixel format of the + * output stream that is used to produce the reprocessing data may be any + * format reported by android.scaler.availableStreamConfigurations. The + * supported input/output stream combinations depends the camera device + * capabilities, see android.scaler.availableInputOutputFormatsMap for + * stream map details. + * + * This kind of stream is generally used to reprocess data into higher + * quality images (that otherwise would cause a frame rate performance + * loss), or to do off-line reprocessing. + * + * CAMERA_DEVICE_API_VERSION_3_3: + * The typical use cases are OPAQUE (typically ZSL) and YUV reprocessing, + * see S8.2, S8.3 and S10 for more details. + */ + CAMERA3_STREAM_INPUT = 1, + + /** + * This stream can be used for input and output. Typically, the stream is + * used as an output stream, but occasionally one already-filled buffer may + * be sent back to the HAL device for reprocessing. + * + * This kind of stream is meant generally for Zero Shutter Lag (ZSL) + * features, where copying the captured image from the output buffer to the + * reprocessing input buffer would be expensive. See S8.1 for more details. + * + * Note that the HAL will always be reprocessing data it produced. + * + */ + CAMERA3_STREAM_BIDIRECTIONAL = 2, + + /** + * Total number of framework-defined stream types + */ + CAMERA3_NUM_STREAM_TYPES + +} camera3_stream_type_t; + +/** + * camera3_stream_rotation_t: + * + * The required counterclockwise rotation of camera stream. + */ +typedef enum camera3_stream_rotation { + /* No rotation */ + CAMERA3_STREAM_ROTATION_0 = 0, + + /* Rotate by 90 degree counterclockwise */ + CAMERA3_STREAM_ROTATION_90 = 1, + + /* Rotate by 180 degree counterclockwise */ + CAMERA3_STREAM_ROTATION_180 = 2, + + /* Rotate by 270 degree counterclockwise */ + CAMERA3_STREAM_ROTATION_270 = 3 +} camera3_stream_rotation_t; + +/** + * camera3_stream_configuration_mode_t: + * + * This defines the general operation mode for the HAL (for a given stream configuration), where + * modes besides NORMAL have different semantics, and usually limit the generality of the API in + * exchange for higher performance in some particular area. + */ +typedef enum camera3_stream_configuration_mode { + /** + * Normal stream configuration operation mode. This is the default camera operation mode, + * where all semantics of HAL APIs and metadata controls apply. + */ + CAMERA3_STREAM_CONFIGURATION_NORMAL_MODE = 0, + + /** + * Special constrained high speed operation mode for devices that can not support high + * speed output in NORMAL mode. All streams in this configuration are operating at high speed + * mode and have different characteristics and limitations to achieve high speed output. + * The NORMAL mode can still be used for high speed output if the HAL can support high speed + * output while satisfying all the semantics of HAL APIs and metadata controls. It is + * recommended for the HAL to support high speed output in NORMAL mode (by advertising the high + * speed FPS ranges in android.control.aeAvailableTargetFpsRanges) if possible. + * + * This mode has below limitations/requirements: + * + * 1. The HAL must support up to 2 streams with sizes reported by + * android.control.availableHighSpeedVideoConfigurations. + * 2. In this mode, the HAL is expected to output up to 120fps or higher. This mode must + * support the targeted FPS range and size configurations reported by + * android.control.availableHighSpeedVideoConfigurations. + * 3. The HAL must support HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED output stream format. + * 4. To achieve efficient high speed streaming, the HAL may have to aggregate + * multiple frames together and send to camera device for processing where the request + * controls are same for all the frames in this batch (batch mode). The HAL must support + * max batch size and the max batch size requirements defined by + * android.control.availableHighSpeedVideoConfigurations. + * 5. In this mode, the HAL must override aeMode, awbMode, and afMode to ON, ON, and + * CONTINUOUS_VIDEO, respectively. All post-processing block mode controls must be + * overridden to be FAST. Therefore, no manual control of capture and post-processing + * parameters is possible. All other controls operate the same as when + * android.control.mode == AUTO. This means that all other android.control.* fields + * must continue to work, such as + * + * android.control.aeTargetFpsRange + * android.control.aeExposureCompensation + * android.control.aeLock + * android.control.awbLock + * android.control.effectMode + * android.control.aeRegions + * android.control.afRegions + * android.control.awbRegions + * android.control.afTrigger + * android.control.aePrecaptureTrigger + * + * Outside of android.control.*, the following controls must work: + * + * android.flash.mode (TORCH mode only, automatic flash for still capture will not work + * since aeMode is ON) + * android.lens.opticalStabilizationMode (if it is supported) + * android.scaler.cropRegion + * android.statistics.faceDetectMode (if it is supported) + * + * For more details about high speed stream requirements, see + * android.control.availableHighSpeedVideoConfigurations and CONSTRAINED_HIGH_SPEED_VIDEO + * capability defined in android.request.availableCapabilities. + * + * This mode only needs to be supported by HALs that include CONSTRAINED_HIGH_SPEED_VIDEO in + * the android.request.availableCapabilities static metadata. + */ + CAMERA3_STREAM_CONFIGURATION_CONSTRAINED_HIGH_SPEED_MODE = 1, + + /** + * First value for vendor-defined stream configuration modes. + */ + CAMERA3_VENDOR_STREAM_CONFIGURATION_MODE_START = 0x8000 +} camera3_stream_configuration_mode_t; + +/** + * camera3_stream_t: + * + * A handle to a single camera input or output stream. A stream is defined by + * the framework by its buffer resolution and format, and additionally by the + * HAL with the gralloc usage flags and the maximum in-flight buffer count. + * + * The stream structures are owned by the framework, but pointers to a + * camera3_stream passed into the HAL by configure_streams() are valid until the + * end of the first subsequent configure_streams() call that _does not_ include + * that camera3_stream as an argument, or until the end of the close() call. + * + * All camera3_stream framework-controlled members are immutable once the + * camera3_stream is passed into configure_streams(). The HAL may only change + * the HAL-controlled parameters during a configure_streams() call, except for + * the contents of the private pointer. + * + * If a configure_streams() call returns a non-fatal error, all active streams + * remain valid as if configure_streams() had not been called. + * + * The endpoint of the stream is not visible to the camera HAL device. + * In DEVICE_API_VERSION_3_1, this was changed to share consumer usage flags + * on streams where the camera is a producer (OUTPUT and BIDIRECTIONAL stream + * types) see the usage field below. + */ +typedef struct camera3_stream { + + /***** + * Set by framework before configure_streams() + */ + + /** + * The type of the stream, one of the camera3_stream_type_t values. + */ + int stream_type; + + /** + * The width in pixels of the buffers in this stream + */ + uint32_t width; + + /** + * The height in pixels of the buffers in this stream + */ + uint32_t height; + + /** + * The pixel format for the buffers in this stream. Format is a value from + * the HAL_PIXEL_FORMAT_* list in system/core/include/system/graphics.h, or + * from device-specific headers. + * + * If HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED is used, then the platform + * gralloc module will select a format based on the usage flags provided by + * the camera device and the other endpoint of the stream. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * The camera HAL device must inspect the buffers handed to it in the + * subsequent register_stream_buffers() call to obtain the + * implementation-specific format details, if necessary. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * register_stream_buffers() won't be called by the framework, so the HAL + * should configure the ISP and sensor pipeline based purely on the sizes, + * usage flags, and formats for the configured streams. + */ + int format; + + /***** + * Set by HAL during configure_streams(). + */ + + /** + * The gralloc usage flags for this stream, as needed by the HAL. The usage + * flags are defined in gralloc.h (GRALLOC_USAGE_*), or in device-specific + * headers. + * + * For output streams, these are the HAL's producer usage flags. For input + * streams, these are the HAL's consumer usage flags. The usage flags from + * the producer and the consumer will be combined together and then passed + * to the platform gralloc HAL module for allocating the gralloc buffers for + * each stream. + * + * Version information: + * + * == CAMERA_DEVICE_API_VERSION_3_0: + * + * No initial value guaranteed when passed via configure_streams(). + * HAL may not use this field as input, and must write over this field + * with its usage flags. + * + * >= CAMERA_DEVICE_API_VERSION_3_1: + * + * For stream_type OUTPUT and BIDIRECTIONAL, when passed via + * configure_streams(), the initial value of this is the consumer's + * usage flags. The HAL may use these consumer flags to decide stream + * configuration. + * For stream_type INPUT, when passed via configure_streams(), the initial + * value of this is 0. + * For all streams passed via configure_streams(), the HAL must write + * over this field with its usage flags. + */ + uint32_t usage; + + /** + * The maximum number of buffers the HAL device may need to have dequeued at + * the same time. The HAL device may not have more buffers in-flight from + * this stream than this value. + */ + uint32_t max_buffers; + + /** + * A handle to HAL-private information for the stream. Will not be inspected + * by the framework code. + */ + void *priv; + + /** + * A field that describes the contents of the buffer. The format and buffer + * dimensions define the memory layout and structure of the stream buffers, + * while dataSpace defines the meaning of the data within the buffer. + * + * For most formats, dataSpace defines the color space of the image data. + * In addition, for some formats, dataSpace indicates whether image- or + * depth-based data is requested. See system/core/include/system/graphics.h + * for details of formats and valid dataSpace values for each format. + * + * Version information: + * + * < CAMERA_DEVICE_API_VERSION_3_3: + * + * Not defined and should not be accessed. dataSpace should be assumed to + * be HAL_DATASPACE_UNKNOWN, and the appropriate color space, etc, should + * be determined from the usage flags and the format. + * + * >= CAMERA_DEVICE_API_VERSION_3_3: + * + * Always set by the camera service. HAL must use this dataSpace to + * configure the stream to the correct colorspace, or to select between + * color and depth outputs if supported. + */ + android_dataspace_t data_space; + + /** + * The required output rotation of the stream, one of + * the camera3_stream_rotation_t values. This must be inspected by HAL along + * with stream width and height. For example, if the rotation is 90 degree + * and the stream width and height is 720 and 1280 respectively, camera service + * will supply buffers of size 720x1280, and HAL should capture a 1280x720 image + * and rotate the image by 90 degree counterclockwise. The rotation field is + * no-op when the stream type is input. Camera HAL must ignore the rotation + * field for an input stream. + * + * <= CAMERA_DEVICE_API_VERSION_3_2: + * + * Not defined and must not be accessed. HAL must not apply any rotation + * on output images. + * + * >= CAMERA_DEVICE_API_VERSION_3_3: + * + * Always set by camera service. HAL must inspect this field during stream + * configuration and returns -EINVAL if HAL cannot perform such rotation. + * HAL must always support CAMERA3_STREAM_ROTATION_0, so a + * configure_streams() call must not fail for unsupported rotation if + * rotation field of all streams is CAMERA3_STREAM_ROTATION_0. + * + */ + int rotation; + + /* reserved for future use */ + void *reserved[7]; + +} camera3_stream_t; + +/** + * camera3_stream_configuration_t: + * + * A structure of stream definitions, used by configure_streams(). This + * structure defines all the output streams and the reprocessing input + * stream for the current camera use case. + */ +typedef struct camera3_stream_configuration { + /** + * The total number of streams requested by the framework. This includes + * both input and output streams. The number of streams will be at least 1, + * and there will be at least one output-capable stream. + */ + uint32_t num_streams; + + /** + * An array of camera stream pointers, defining the input/output + * configuration for the camera HAL device. + * + * At most one input-capable stream may be defined (INPUT or BIDIRECTIONAL) + * in a single configuration. + * + * At least one output-capable stream must be defined (OUTPUT or + * BIDIRECTIONAL). + */ + camera3_stream_t **streams; + + /** + * >= CAMERA_DEVICE_API_VERSION_3_3: + * + * The operation mode of streams in this configuration, one of the value defined in + * camera3_stream_configuration_mode_t. + * The HAL can use this mode as an indicator to set the stream property (e.g., + * camera3_stream->max_buffers) appropriately. For example, if the configuration is + * CAMERA3_STREAM_CONFIGURATION_CONSTRAINED_HIGH_SPEED_MODE, the HAL may want to set aside more + * buffers for batch mode operation (see android.control.availableHighSpeedVideoConfigurations + * for batch mode definition). + * + */ + uint32_t operation_mode; +} camera3_stream_configuration_t; + +/** + * camera3_buffer_status_t: + * + * The current status of a single stream buffer. + */ +typedef enum camera3_buffer_status { + /** + * The buffer is in a normal state, and can be used after waiting on its + * sync fence. + */ + CAMERA3_BUFFER_STATUS_OK = 0, + + /** + * The buffer does not contain valid data, and the data in it should not be + * used. The sync fence must still be waited on before reusing the buffer. + */ + CAMERA3_BUFFER_STATUS_ERROR = 1 + +} camera3_buffer_status_t; + +/** + * camera3_stream_buffer_t: + * + * A single buffer from a camera3 stream. It includes a handle to its parent + * stream, the handle to the gralloc buffer itself, and sync fences + * + * The buffer does not specify whether it is to be used for input or output; + * that is determined by its parent stream type and how the buffer is passed to + * the HAL device. + */ +typedef struct camera3_stream_buffer { + /** + * The handle of the stream this buffer is associated with + */ + camera3_stream_t *stream; + + /** + * The native handle to the buffer + */ + buffer_handle_t *buffer; + + /** + * Current state of the buffer, one of the camera3_buffer_status_t + * values. The framework will not pass buffers to the HAL that are in an + * error state. In case a buffer could not be filled by the HAL, it must + * have its status set to CAMERA3_BUFFER_STATUS_ERROR when returned to the + * framework with process_capture_result(). + */ + int status; + + /** + * The acquire sync fence for this buffer. The HAL must wait on this fence + * fd before attempting to read from or write to this buffer. + * + * The framework may be set to -1 to indicate that no waiting is necessary + * for this buffer. + * + * When the HAL returns an output buffer to the framework with + * process_capture_result(), the acquire_fence must be set to -1. If the HAL + * never waits on the acquire_fence due to an error in filling a buffer, + * when calling process_capture_result() the HAL must set the release_fence + * of the buffer to be the acquire_fence passed to it by the framework. This + * will allow the framework to wait on the fence before reusing the buffer. + * + * For input buffers, the HAL must not change the acquire_fence field during + * the process_capture_request() call. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * When the HAL returns an input buffer to the framework with + * process_capture_result(), the acquire_fence must be set to -1. If the HAL + * never waits on input buffer acquire fence due to an error, the sync + * fences should be handled similarly to the way they are handled for output + * buffers. + */ + int acquire_fence; + + /** + * The release sync fence for this buffer. The HAL must set this fence when + * returning buffers to the framework, or write -1 to indicate that no + * waiting is required for this buffer. + * + * For the output buffers, the fences must be set in the output_buffers + * array passed to process_capture_result(). + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * For the input buffer, the release fence must be set by the + * process_capture_request() call. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * For the input buffer, the fences must be set in the input_buffer + * passed to process_capture_result(). + * + * After signaling the release_fence for this buffer, the HAL + * should not make any further attempts to access this buffer as the + * ownership has been fully transferred back to the framework. + * + * If a fence of -1 was specified then the ownership of this buffer + * is transferred back immediately upon the call of process_capture_result. + */ + int release_fence; + +} camera3_stream_buffer_t; + +/** + * camera3_stream_buffer_set_t: + * + * The complete set of gralloc buffers for a stream. This structure is given to + * register_stream_buffers() to allow the camera HAL device to register/map/etc + * newly allocated stream buffers. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Deprecated (and not used). In particular, + * register_stream_buffers is also deprecated and will never be invoked. + * + */ +typedef struct camera3_stream_buffer_set { + /** + * The stream handle for the stream these buffers belong to + */ + camera3_stream_t *stream; + + /** + * The number of buffers in this stream. It is guaranteed to be at least + * stream->max_buffers. + */ + uint32_t num_buffers; + + /** + * The array of gralloc buffer handles for this stream. If the stream format + * is set to HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED, the camera HAL device + * should inspect the passed-in buffers to determine any platform-private + * pixel format information. + */ + buffer_handle_t **buffers; + +} camera3_stream_buffer_set_t; + +/** + * camera3_jpeg_blob: + * + * Transport header for compressed JPEG buffers in output streams. + * + * To capture JPEG images, a stream is created using the pixel format + * HAL_PIXEL_FORMAT_BLOB. The buffer size for the stream is calculated by the + * framework, based on the static metadata field android.jpeg.maxSize. Since + * compressed JPEG images are of variable size, the HAL needs to include the + * final size of the compressed image using this structure inside the output + * stream buffer. The JPEG blob ID field must be set to CAMERA3_JPEG_BLOB_ID. + * + * Transport header should be at the end of the JPEG output stream buffer. That + * means the jpeg_blob_id must start at byte[buffer_size - + * sizeof(camera3_jpeg_blob)], where the buffer_size is the size of gralloc buffer. + * Any HAL using this transport header must account for it in android.jpeg.maxSize + * The JPEG data itself starts at the beginning of the buffer and should be + * jpeg_size bytes long. + */ +typedef struct camera3_jpeg_blob { + uint16_t jpeg_blob_id; + uint32_t jpeg_size; +} camera3_jpeg_blob_t; + +enum { + CAMERA3_JPEG_BLOB_ID = 0x00FF +}; + +/********************************************************************** + * + * Message definitions for the HAL notify() callback. + * + * These definitions are used for the HAL notify callback, to signal + * asynchronous events from the HAL device to the Android framework. + * + */ + +/** + * camera3_msg_type: + * + * Indicates the type of message sent, which specifies which member of the + * message union is valid. + * + */ +typedef enum camera3_msg_type { + /** + * An error has occurred. camera3_notify_msg.message.error contains the + * error information. + */ + CAMERA3_MSG_ERROR = 1, + + /** + * The exposure of a given request or processing a reprocess request has + * begun. camera3_notify_msg.message.shutter contains the information + * the capture. + */ + CAMERA3_MSG_SHUTTER = 2, + + /** + * Number of framework message types + */ + CAMERA3_NUM_MESSAGES + +} camera3_msg_type_t; + +/** + * Defined error codes for CAMERA_MSG_ERROR + */ +typedef enum camera3_error_msg_code { + /** + * A serious failure occured. No further frames or buffer streams will + * be produced by the device. Device should be treated as closed. The + * client must reopen the device to use it again. The frame_number field + * is unused. + */ + CAMERA3_MSG_ERROR_DEVICE = 1, + + /** + * An error has occurred in processing a request. No output (metadata or + * buffers) will be produced for this request. The frame_number field + * specifies which request has been dropped. Subsequent requests are + * unaffected, and the device remains operational. + */ + CAMERA3_MSG_ERROR_REQUEST = 2, + + /** + * An error has occurred in producing an output result metadata buffer + * for a request, but output stream buffers for it will still be + * available. Subsequent requests are unaffected, and the device remains + * operational. The frame_number field specifies the request for which + * result metadata won't be available. + */ + CAMERA3_MSG_ERROR_RESULT = 3, + + /** + * An error has occurred in placing an output buffer into a stream for a + * request. The frame metadata and other buffers may still be + * available. Subsequent requests are unaffected, and the device remains + * operational. The frame_number field specifies the request for which the + * buffer was dropped, and error_stream contains a pointer to the stream + * that dropped the frame.u + */ + CAMERA3_MSG_ERROR_BUFFER = 4, + + /** + * Number of error types + */ + CAMERA3_MSG_NUM_ERRORS + +} camera3_error_msg_code_t; + +/** + * camera3_error_msg_t: + * + * Message contents for CAMERA3_MSG_ERROR + */ +typedef struct camera3_error_msg { + /** + * Frame number of the request the error applies to. 0 if the frame number + * isn't applicable to the error. + */ + uint32_t frame_number; + + /** + * Pointer to the stream that had a failure. NULL if the stream isn't + * applicable to the error. + */ + camera3_stream_t *error_stream; + + /** + * The code for this error; one of the CAMERA_MSG_ERROR enum values. + */ + int error_code; + +} camera3_error_msg_t; + +/** + * camera3_shutter_msg_t: + * + * Message contents for CAMERA3_MSG_SHUTTER + */ +typedef struct camera3_shutter_msg { + /** + * Frame number of the request that has begun exposure or reprocessing. + */ + uint32_t frame_number; + + /** + * Timestamp for the start of capture. For a reprocess request, this must + * be input image's start of capture. This must match the capture result + * metadata's sensor exposure start timestamp. + */ + uint64_t timestamp; + +} camera3_shutter_msg_t; + +/** + * camera3_notify_msg_t: + * + * The message structure sent to camera3_callback_ops_t.notify() + */ +typedef struct camera3_notify_msg { + + /** + * The message type. One of camera3_notify_msg_type, or a private extension. + */ + int type; + + union { + /** + * Error message contents. Valid if type is CAMERA3_MSG_ERROR + */ + camera3_error_msg_t error; + + /** + * Shutter message contents. Valid if type is CAMERA3_MSG_SHUTTER + */ + camera3_shutter_msg_t shutter; + + /** + * Generic message contents. Used to ensure a minimum size for custom + * message types. + */ + uint8_t generic[32]; + } message; + +} camera3_notify_msg_t; + +/********************************************************************** + * + * Capture request/result definitions for the HAL process_capture_request() + * method, and the process_capture_result() callback. + * + */ + +/** + * camera3_request_template_t: + * + * Available template types for + * camera3_device_ops.construct_default_request_settings() + */ +typedef enum camera3_request_template { + /** + * Standard camera preview operation with 3A on auto. + */ + CAMERA3_TEMPLATE_PREVIEW = 1, + + /** + * Standard camera high-quality still capture with 3A and flash on auto. + */ + CAMERA3_TEMPLATE_STILL_CAPTURE = 2, + + /** + * Standard video recording plus preview with 3A on auto, torch off. + */ + CAMERA3_TEMPLATE_VIDEO_RECORD = 3, + + /** + * High-quality still capture while recording video. Application will + * include preview, video record, and full-resolution YUV or JPEG streams in + * request. Must not cause stuttering on video stream. 3A on auto. + */ + CAMERA3_TEMPLATE_VIDEO_SNAPSHOT = 4, + + /** + * Zero-shutter-lag mode. Application will request preview and + * full-resolution data for each frame, and reprocess it to JPEG when a + * still image is requested by user. Settings should provide highest-quality + * full-resolution images without compromising preview frame rate. 3A on + * auto. + */ + CAMERA3_TEMPLATE_ZERO_SHUTTER_LAG = 5, + + /** + * A basic template for direct application control of capture + * parameters. All automatic control is disabled (auto-exposure, auto-white + * balance, auto-focus), and post-processing parameters are set to preview + * quality. The manual capture parameters (exposure, sensitivity, etc.) + * are set to reasonable defaults, but should be overridden by the + * application depending on the intended use case. + */ + CAMERA3_TEMPLATE_MANUAL = 6, + + /* Total number of templates */ + CAMERA3_TEMPLATE_COUNT, + + /** + * First value for vendor-defined request templates + */ + CAMERA3_VENDOR_TEMPLATE_START = 0x40000000 + +} camera3_request_template_t; + +/** + * camera3_capture_request_t: + * + * A single request for image capture/buffer reprocessing, sent to the Camera + * HAL device by the framework in process_capture_request(). + * + * The request contains the settings to be used for this capture, and the set of + * output buffers to write the resulting image data in. It may optionally + * contain an input buffer, in which case the request is for reprocessing that + * input buffer instead of capturing a new image with the camera sensor. The + * capture is identified by the frame_number. + * + * In response, the camera HAL device must send a camera3_capture_result + * structure asynchronously to the framework, using the process_capture_result() + * callback. + */ +typedef struct camera3_capture_request { + /** + * The frame number is an incrementing integer set by the framework to + * uniquely identify this capture. It needs to be returned in the result + * call, and is also used to identify the request in asynchronous + * notifications sent to camera3_callback_ops_t.notify(). + */ + uint32_t frame_number; + + /** + * The settings buffer contains the capture and processing parameters for + * the request. As a special case, a NULL settings buffer indicates that the + * settings are identical to the most-recently submitted capture request. A + * NULL buffer cannot be used as the first submitted request after a + * configure_streams() call. + */ + const camera_metadata_t *settings; + + /** + * The input stream buffer to use for this request, if any. + * + * If input_buffer is NULL, then the request is for a new capture from the + * imager. If input_buffer is valid, the request is for reprocessing the + * image contained in input_buffer. + * + * In the latter case, the HAL must set the release_fence of the + * input_buffer to a valid sync fence, or to -1 if the HAL does not support + * sync, before process_capture_request() returns. + * + * The HAL is required to wait on the acquire sync fence of the input buffer + * before accessing it. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * Any input buffer included here will have been registered with the HAL + * through register_stream_buffers() before its inclusion in a request. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The buffers will not have been pre-registered with the HAL. + * Subsequent requests may reuse buffers, or provide entirely new buffers. + */ + camera3_stream_buffer_t *input_buffer; + + /** + * The number of output buffers for this capture request. Must be at least + * 1. + */ + uint32_t num_output_buffers; + + /** + * An array of num_output_buffers stream buffers, to be filled with image + * data from this capture/reprocess. The HAL must wait on the acquire fences + * of each stream buffer before writing to them. + * + * The HAL takes ownership of the actual buffer_handle_t entries in + * output_buffers; the framework does not access them until they are + * returned in a camera3_capture_result_t. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * All the buffers included here will have been registered with the HAL + * through register_stream_buffers() before their inclusion in a request. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Any or all of the buffers included here may be brand new in this + * request (having never before seen by the HAL). + */ + const camera3_stream_buffer_t *output_buffers; + +} camera3_capture_request_t; + +/** + * camera3_capture_result_t: + * + * The result of a single capture/reprocess by the camera HAL device. This is + * sent to the framework asynchronously with process_capture_result(), in + * response to a single capture request sent to the HAL with + * process_capture_request(). Multiple process_capture_result() calls may be + * performed by the HAL for each request. + * + * Each call, all with the same frame + * number, may contain some subset of the output buffers, and/or the result + * metadata. The metadata may only be provided once for a given frame number; + * all other calls must set the result metadata to NULL. + * + * The result structure contains the output metadata from this capture, and the + * set of output buffers that have been/will be filled for this capture. Each + * output buffer may come with a release sync fence that the framework will wait + * on before reading, in case the buffer has not yet been filled by the HAL. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The metadata may be provided multiple times for a single frame number. The + * framework will accumulate together the final result set by combining each + * partial result together into the total result set. + * + * If an input buffer is given in a request, the HAL must return it in one of + * the process_capture_result calls, and the call may be to just return the input + * buffer, without metadata and output buffers; the sync fences must be handled + * the same way they are done for output buffers. + * + * + * Performance considerations: + * + * Applications will also receive these partial results immediately, so sending + * partial results is a highly recommended performance optimization to avoid + * the total pipeline latency before sending the results for what is known very + * early on in the pipeline. + * + * A typical use case might be calculating the AF state halfway through the + * pipeline; by sending the state back to the framework immediately, we get a + * 50% performance increase and perceived responsiveness of the auto-focus. + * + */ +typedef struct camera3_capture_result { + /** + * The frame number is an incrementing integer set by the framework in the + * submitted request to uniquely identify this capture. It is also used to + * identify the request in asynchronous notifications sent to + * camera3_callback_ops_t.notify(). + */ + uint32_t frame_number; + + /** + * The result metadata for this capture. This contains information about the + * final capture parameters, the state of the capture and post-processing + * hardware, the state of the 3A algorithms, if enabled, and the output of + * any enabled statistics units. + * + * Only one call to process_capture_result() with a given frame_number may + * include the result metadata. All other calls for the same frame_number + * must set this to NULL. + * + * If there was an error producing the result metadata, result must be an + * empty metadata buffer, and notify() must be called with ERROR_RESULT. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Multiple calls to process_capture_result() with a given frame_number + * may include the result metadata. + * + * Partial metadata submitted should not include any metadata key returned + * in a previous partial result for a given frame. Each new partial result + * for that frame must also set a distinct partial_result value. + * + * If notify has been called with ERROR_RESULT, all further partial + * results for that frame are ignored by the framework. + */ + const camera_metadata_t *result; + + /** + * The number of output buffers returned in this result structure. Must be + * less than or equal to the matching capture request's count. If this is + * less than the buffer count in the capture request, at least one more call + * to process_capture_result with the same frame_number must be made, to + * return the remaining output buffers to the framework. This may only be + * zero if the structure includes valid result metadata or an input buffer + * is returned in this result. + */ + uint32_t num_output_buffers; + + /** + * The handles for the output stream buffers for this capture. They may not + * yet be filled at the time the HAL calls process_capture_result(); the + * framework will wait on the release sync fences provided by the HAL before + * reading the buffers. + * + * The HAL must set the stream buffer's release sync fence to a valid sync + * fd, or to -1 if the buffer has already been filled. + * + * If the HAL encounters an error while processing the buffer, and the + * buffer is not filled, the buffer's status field must be set to + * CAMERA3_BUFFER_STATUS_ERROR. If the HAL did not wait on the acquire fence + * before encountering the error, the acquire fence should be copied into + * the release fence, to allow the framework to wait on the fence before + * reusing the buffer. + * + * The acquire fence must be set to -1 for all output buffers. If + * num_output_buffers is zero, this may be NULL. In that case, at least one + * more process_capture_result call must be made by the HAL to provide the + * output buffers. + * + * When process_capture_result is called with a new buffer for a frame, + * all previous frames' buffers for that corresponding stream must have been + * already delivered (the fences need not have yet been signaled). + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Gralloc buffers for a frame may be sent to framework before the + * corresponding SHUTTER-notify. + * + * Performance considerations: + * + * Buffers delivered to the framework will not be dispatched to the + * application layer until a start of exposure timestamp has been received + * via a SHUTTER notify() call. It is highly recommended to + * dispatch that call as early as possible. + */ + const camera3_stream_buffer_t *output_buffers; + + /** + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The handle for the input stream buffer for this capture. It may not + * yet be consumed at the time the HAL calls process_capture_result(); the + * framework will wait on the release sync fences provided by the HAL before + * reusing the buffer. + * + * The HAL should handle the sync fences the same way they are done for + * output_buffers. + * + * Only one input buffer is allowed to be sent per request. Similarly to + * output buffers, the ordering of returned input buffers must be + * maintained by the HAL. + * + * Performance considerations: + * + * The input buffer should be returned as early as possible. If the HAL + * supports sync fences, it can call process_capture_result to hand it back + * with sync fences being set appropriately. If the sync fences are not + * supported, the buffer can only be returned when it is consumed, which + * may take long time; the HAL may choose to copy this input buffer to make + * the buffer return sooner. + */ + const camera3_stream_buffer_t *input_buffer; + + /** + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * In order to take advantage of partial results, the HAL must set the + * static metadata android.request.partialResultCount to the number of + * partial results it will send for each frame. + * + * Each new capture result with a partial result must set + * this field (partial_result) to a distinct inclusive value between + * 1 and android.request.partialResultCount. + * + * HALs not wishing to take advantage of this feature must not + * set an android.request.partialResultCount or partial_result to a value + * other than 1. + * + * This value must be set to 0 when a capture result contains buffers only + * and no metadata. + */ + uint32_t partial_result; + +} camera3_capture_result_t; + +/********************************************************************** + * + * Callback methods for the HAL to call into the framework. + * + * These methods are used to return metadata and image buffers for a completed + * or failed captures, and to notify the framework of asynchronous events such + * as errors. + * + * The framework will not call back into the HAL from within these callbacks, + * and these calls will not block for extended periods. + * + */ +typedef struct camera3_callback_ops { + + /** + * process_capture_result: + * + * Send results from a completed capture to the framework. + * process_capture_result() may be invoked multiple times by the HAL in + * response to a single capture request. This allows, for example, the + * metadata and low-resolution buffers to be returned in one call, and + * post-processed JPEG buffers in a later call, once it is available. Each + * call must include the frame number of the request it is returning + * metadata or buffers for. + * + * A component (buffer or metadata) of the complete result may only be + * included in one process_capture_result call. A buffer for each stream, + * and the result metadata, must be returned by the HAL for each request in + * one of the process_capture_result calls, even in case of errors producing + * some of the output. A call to process_capture_result() with neither + * output buffers or result metadata is not allowed. + * + * The order of returning metadata and buffers for a single result does not + * matter, but buffers for a given stream must be returned in FIFO order. So + * the buffer for request 5 for stream A must always be returned before the + * buffer for request 6 for stream A. This also applies to the result + * metadata; the metadata for request 5 must be returned before the metadata + * for request 6. + * + * However, different streams are independent of each other, so it is + * acceptable and expected that the buffer for request 5 for stream A may be + * returned after the buffer for request 6 for stream B is. And it is + * acceptable that the result metadata for request 6 for stream B is + * returned before the buffer for request 5 for stream A is. + * + * The HAL retains ownership of result structure, which only needs to be + * valid to access during this call. The framework will copy whatever it + * needs before this call returns. + * + * The output buffers do not need to be filled yet; the framework will wait + * on the stream buffer release sync fence before reading the buffer + * data. Therefore, this method should be called by the HAL as soon as + * possible, even if some or all of the output buffers are still in + * being filled. The HAL must include valid release sync fences into each + * output_buffers stream buffer entry, or -1 if that stream buffer is + * already filled. + * + * If the result buffer cannot be constructed for a request, the HAL should + * return an empty metadata buffer, but still provide the output buffers and + * their sync fences. In addition, notify() must be called with an + * ERROR_RESULT message. + * + * If an output buffer cannot be filled, its status field must be set to + * STATUS_ERROR. In addition, notify() must be called with a ERROR_BUFFER + * message. + * + * If the entire capture has failed, then this method still needs to be + * called to return the output buffers to the framework. All the buffer + * statuses should be STATUS_ERROR, and the result metadata should be an + * empty buffer. In addition, notify() must be called with a ERROR_REQUEST + * message. In this case, individual ERROR_RESULT/ERROR_BUFFER messages + * should not be sent. + * + * Performance requirements: + * + * This is a non-blocking call. The framework will return this call in 5ms. + * + * The pipeline latency (see S7 for definition) should be less than or equal to + * 4 frame intervals, and must be less than or equal to 8 frame intervals. + * + */ + void (*process_capture_result)(const struct camera3_callback_ops *, + const camera3_capture_result_t *result); + + /** + * notify: + * + * Asynchronous notification callback from the HAL, fired for various + * reasons. Only for information independent of frame capture, or that + * require specific timing. The ownership of the message structure remains + * with the HAL, and the msg only needs to be valid for the duration of this + * call. + * + * Multiple threads may call notify() simultaneously. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * The notification for the start of exposure for a given request must be + * sent by the HAL before the first call to process_capture_result() for + * that request is made. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Buffers delivered to the framework will not be dispatched to the + * application layer until a start of exposure timestamp (or input image's + * start of exposure timestamp for a reprocess request) has been received + * via a SHUTTER notify() call. It is highly recommended to dispatch this + * call as early as possible. + * + * ------------------------------------------------------------------------ + * Performance requirements: + * + * This is a non-blocking call. The framework will return this call in 5ms. + */ + void (*notify)(const struct camera3_callback_ops *, + const camera3_notify_msg_t *msg); + +} camera3_callback_ops_t; + +/********************************************************************** + * + * Camera device operations + * + */ +typedef struct camera3_device_ops { + + /** + * initialize: + * + * One-time initialization to pass framework callback function pointers to + * the HAL. Will be called once after a successful open() call, before any + * other functions are called on the camera3_device_ops structure. + * + * Performance requirements: + * + * This should be a non-blocking call. The HAL should return from this call + * in 5ms, and must return from this call in 10ms. + * + * Return values: + * + * 0: On successful initialization + * + * -ENODEV: If initialization fails. Only close() can be called successfully + * by the framework after this. + */ + int (*initialize)(const struct camera3_device *, + const camera3_callback_ops_t *callback_ops); + + /********************************************************************** + * Stream management + */ + + /** + * configure_streams: + * + * CAMERA_DEVICE_API_VERSION_3_0 only: + * + * Reset the HAL camera device processing pipeline and set up new input and + * output streams. This call replaces any existing stream configuration with + * the streams defined in the stream_list. This method will be called at + * least once after initialize() before a request is submitted with + * process_capture_request(). + * + * The stream_list must contain at least one output-capable stream, and may + * not contain more than one input-capable stream. + * + * The stream_list may contain streams that are also in the currently-active + * set of streams (from the previous call to configure_stream()). These + * streams will already have valid values for usage, max_buffers, and the + * private pointer. + * + * If such a stream has already had its buffers registered, + * register_stream_buffers() will not be called again for the stream, and + * buffers from the stream can be immediately included in input requests. + * + * If the HAL needs to change the stream configuration for an existing + * stream due to the new configuration, it may rewrite the values of usage + * and/or max_buffers during the configure call. + * + * The framework will detect such a change, and will then reallocate the + * stream buffers, and call register_stream_buffers() again before using + * buffers from that stream in a request. + * + * If a currently-active stream is not included in stream_list, the HAL may + * safely remove any references to that stream. It will not be reused in a + * later configure() call by the framework, and all the gralloc buffers for + * it will be freed after the configure_streams() call returns. + * + * The stream_list structure is owned by the framework, and may not be + * accessed once this call completes. The address of an individual + * camera3_stream_t structure will remain valid for access by the HAL until + * the end of the first configure_stream() call which no longer includes + * that camera3_stream_t in the stream_list argument. The HAL may not change + * values in the stream structure outside of the private pointer, except for + * the usage and max_buffers members during the configure_streams() call + * itself. + * + * If the stream is new, the usage, max_buffer, and private pointer fields + * of the stream structure will all be set to 0. The HAL device must set + * these fields before the configure_streams() call returns. These fields + * are then used by the framework and the platform gralloc module to + * allocate the gralloc buffers for each stream. + * + * Before such a new stream can have its buffers included in a capture + * request, the framework will call register_stream_buffers() with that + * stream. However, the framework is not required to register buffers for + * _all_ streams before submitting a request. This allows for quick startup + * of (for example) a preview stream, with allocation for other streams + * happening later or concurrently. + * + * ------------------------------------------------------------------------ + * CAMERA_DEVICE_API_VERSION_3_1 only: + * + * Reset the HAL camera device processing pipeline and set up new input and + * output streams. This call replaces any existing stream configuration with + * the streams defined in the stream_list. This method will be called at + * least once after initialize() before a request is submitted with + * process_capture_request(). + * + * The stream_list must contain at least one output-capable stream, and may + * not contain more than one input-capable stream. + * + * The stream_list may contain streams that are also in the currently-active + * set of streams (from the previous call to configure_stream()). These + * streams will already have valid values for usage, max_buffers, and the + * private pointer. + * + * If such a stream has already had its buffers registered, + * register_stream_buffers() will not be called again for the stream, and + * buffers from the stream can be immediately included in input requests. + * + * If the HAL needs to change the stream configuration for an existing + * stream due to the new configuration, it may rewrite the values of usage + * and/or max_buffers during the configure call. + * + * The framework will detect such a change, and will then reallocate the + * stream buffers, and call register_stream_buffers() again before using + * buffers from that stream in a request. + * + * If a currently-active stream is not included in stream_list, the HAL may + * safely remove any references to that stream. It will not be reused in a + * later configure() call by the framework, and all the gralloc buffers for + * it will be freed after the configure_streams() call returns. + * + * The stream_list structure is owned by the framework, and may not be + * accessed once this call completes. The address of an individual + * camera3_stream_t structure will remain valid for access by the HAL until + * the end of the first configure_stream() call which no longer includes + * that camera3_stream_t in the stream_list argument. The HAL may not change + * values in the stream structure outside of the private pointer, except for + * the usage and max_buffers members during the configure_streams() call + * itself. + * + * If the stream is new, max_buffer, and private pointer fields of the + * stream structure will all be set to 0. The usage will be set to the + * consumer usage flags. The HAL device must set these fields before the + * configure_streams() call returns. These fields are then used by the + * framework and the platform gralloc module to allocate the gralloc + * buffers for each stream. + * + * Before such a new stream can have its buffers included in a capture + * request, the framework will call register_stream_buffers() with that + * stream. However, the framework is not required to register buffers for + * _all_ streams before submitting a request. This allows for quick startup + * of (for example) a preview stream, with allocation for other streams + * happening later or concurrently. + * + * ------------------------------------------------------------------------ + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * Reset the HAL camera device processing pipeline and set up new input and + * output streams. This call replaces any existing stream configuration with + * the streams defined in the stream_list. This method will be called at + * least once after initialize() before a request is submitted with + * process_capture_request(). + * + * The stream_list must contain at least one output-capable stream, and may + * not contain more than one input-capable stream. + * + * The stream_list may contain streams that are also in the currently-active + * set of streams (from the previous call to configure_stream()). These + * streams will already have valid values for usage, max_buffers, and the + * private pointer. + * + * If the HAL needs to change the stream configuration for an existing + * stream due to the new configuration, it may rewrite the values of usage + * and/or max_buffers during the configure call. + * + * The framework will detect such a change, and may then reallocate the + * stream buffers before using buffers from that stream in a request. + * + * If a currently-active stream is not included in stream_list, the HAL may + * safely remove any references to that stream. It will not be reused in a + * later configure() call by the framework, and all the gralloc buffers for + * it will be freed after the configure_streams() call returns. + * + * The stream_list structure is owned by the framework, and may not be + * accessed once this call completes. The address of an individual + * camera3_stream_t structure will remain valid for access by the HAL until + * the end of the first configure_stream() call which no longer includes + * that camera3_stream_t in the stream_list argument. The HAL may not change + * values in the stream structure outside of the private pointer, except for + * the usage and max_buffers members during the configure_streams() call + * itself. + * + * If the stream is new, max_buffer, and private pointer fields of the + * stream structure will all be set to 0. The usage will be set to the + * consumer usage flags. The HAL device must set these fields before the + * configure_streams() call returns. These fields are then used by the + * framework and the platform gralloc module to allocate the gralloc + * buffers for each stream. + * + * Newly allocated buffers may be included in a capture request at any time + * by the framework. Once a gralloc buffer is returned to the framework + * with process_capture_result (and its respective release_fence has been + * signaled) the framework may free or reuse it at any time. + * + * ------------------------------------------------------------------------ + * + * Preconditions: + * + * The framework will only call this method when no captures are being + * processed. That is, all results have been returned to the framework, and + * all in-flight input and output buffers have been returned and their + * release sync fences have been signaled by the HAL. The framework will not + * submit new requests for capture while the configure_streams() call is + * underway. + * + * Postconditions: + * + * The HAL device must configure itself to provide maximum possible output + * frame rate given the sizes and formats of the output streams, as + * documented in the camera device's static metadata. + * + * Performance requirements: + * + * This call is expected to be heavyweight and possibly take several hundred + * milliseconds to complete, since it may require resetting and + * reconfiguring the image sensor and the camera processing pipeline. + * Nevertheless, the HAL device should attempt to minimize the + * reconfiguration delay to minimize the user-visible pauses during + * application operational mode changes (such as switching from still + * capture to video recording). + * + * The HAL should return from this call in 500ms, and must return from this + * call in 1000ms. + * + * Return values: + * + * 0: On successful stream configuration + * + * -EINVAL: If the requested stream configuration is invalid. Some examples + * of invalid stream configurations include: + * + * - Including more than 1 input-capable stream (INPUT or + * BIDIRECTIONAL) + * + * - Not including any output-capable streams (OUTPUT or + * BIDIRECTIONAL) + * + * - Including streams with unsupported formats, or an unsupported + * size for that format. + * + * - Including too many output streams of a certain format. + * + * - Unsupported rotation configuration (only applies to + * devices with version >= CAMERA_DEVICE_API_VERSION_3_3) + * + * - Stream sizes/formats don't satisfy the + * camera3_stream_configuration_t->operation_mode requirements for non-NORMAL mode, + * or the requested operation_mode is not supported by the HAL. + * (only applies to devices with version >= CAMERA_DEVICE_API_VERSION_3_3) + * + * Note that the framework submitting an invalid stream + * configuration is not normal operation, since stream + * configurations are checked before configure. An invalid + * configuration means that a bug exists in the framework code, or + * there is a mismatch between the HAL's static metadata and the + * requirements on streams. + * + * -ENODEV: If there has been a fatal error and the device is no longer + * operational. Only close() can be called successfully by the + * framework after this error is returned. + */ + int (*configure_streams)(const struct camera3_device *, + camera3_stream_configuration_t *stream_list); + + /** + * register_stream_buffers: + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * DEPRECATED. This will not be called and must be set to NULL. + * + * <= CAMERA_DEVICE_API_VERSION_3_1: + * + * Register buffers for a given stream with the HAL device. This method is + * called by the framework after a new stream is defined by + * configure_streams, and before buffers from that stream are included in a + * capture request. If the same stream is listed in a subsequent + * configure_streams() call, register_stream_buffers will _not_ be called + * again for that stream. + * + * The framework does not need to register buffers for all configured + * streams before it submits the first capture request. This allows quick + * startup for preview (or similar use cases) while other streams are still + * being allocated. + * + * This method is intended to allow the HAL device to map or otherwise + * prepare the buffers for later use. The buffers passed in will already be + * locked for use. At the end of the call, all the buffers must be ready to + * be returned to the stream. The buffer_set argument is only valid for the + * duration of this call. + * + * If the stream format was set to HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED, + * the camera HAL should inspect the passed-in buffers here to determine any + * platform-private pixel format information. + * + * Performance requirements: + * + * This should be a non-blocking call. The HAL should return from this call + * in 1ms, and must return from this call in 5ms. + * + * Return values: + * + * 0: On successful registration of the new stream buffers + * + * -EINVAL: If the stream_buffer_set does not refer to a valid active + * stream, or if the buffers array is invalid. + * + * -ENOMEM: If there was a failure in registering the buffers. The framework + * must consider all the stream buffers to be unregistered, and can + * try to register again later. + * + * -ENODEV: If there is a fatal error, and the device is no longer + * operational. Only close() can be called successfully by the + * framework after this error is returned. + */ + int (*register_stream_buffers)(const struct camera3_device *, + const camera3_stream_buffer_set_t *buffer_set); + + /********************************************************************** + * Request creation and submission + */ + + /** + * construct_default_request_settings: + * + * Create capture settings for standard camera use cases. + * + * The device must return a settings buffer that is configured to meet the + * requested use case, which must be one of the CAMERA3_TEMPLATE_* + * enums. All request control fields must be included. + * + * The HAL retains ownership of this structure, but the pointer to the + * structure must be valid until the device is closed. The framework and the + * HAL may not modify the buffer once it is returned by this call. The same + * buffer may be returned for subsequent calls for the same template, or for + * other templates. + * + * Performance requirements: + * + * This should be a non-blocking call. The HAL should return from this call + * in 1ms, and must return from this call in 5ms. + * + * Return values: + * + * Valid metadata: On successful creation of a default settings + * buffer. + * + * NULL: In case of a fatal error. After this is returned, only + * the close() method can be called successfully by the + * framework. + */ + const camera_metadata_t* (*construct_default_request_settings)( + const struct camera3_device *, + int type); + + /** + * process_capture_request: + * + * Send a new capture request to the HAL. The HAL should not return from + * this call until it is ready to accept the next request to process. Only + * one call to process_capture_request() will be made at a time by the + * framework, and the calls will all be from the same thread. The next call + * to process_capture_request() will be made as soon as a new request and + * its associated buffers are available. In a normal preview scenario, this + * means the function will be called again by the framework almost + * instantly. + * + * The actual request processing is asynchronous, with the results of + * capture being returned by the HAL through the process_capture_result() + * call. This call requires the result metadata to be available, but output + * buffers may simply provide sync fences to wait on. Multiple requests are + * expected to be in flight at once, to maintain full output frame rate. + * + * The framework retains ownership of the request structure. It is only + * guaranteed to be valid during this call. The HAL device must make copies + * of the information it needs to retain for the capture processing. The HAL + * is responsible for waiting on and closing the buffers' fences and + * returning the buffer handles to the framework. + * + * The HAL must write the file descriptor for the input buffer's release + * sync fence into input_buffer->release_fence, if input_buffer is not + * NULL. If the HAL returns -1 for the input buffer release sync fence, the + * framework is free to immediately reuse the input buffer. Otherwise, the + * framework will wait on the sync fence before refilling and reusing the + * input buffer. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * + * The input/output buffers provided by the framework in each request + * may be brand new (having never before seen by the HAL). + * + * ------------------------------------------------------------------------ + * Performance considerations: + * + * Handling a new buffer should be extremely lightweight and there should be + * no frame rate degradation or frame jitter introduced. + * + * This call must return fast enough to ensure that the requested frame + * rate can be sustained, especially for streaming cases (post-processing + * quality settings set to FAST). The HAL should return this call in 1 + * frame interval, and must return from this call in 4 frame intervals. + * + * Return values: + * + * 0: On a successful start to processing the capture request + * + * -EINVAL: If the input is malformed (the settings are NULL when not + * allowed, there are 0 output buffers, etc) and capture processing + * cannot start. Failures during request processing should be + * handled by calling camera3_callback_ops_t.notify(). In case of + * this error, the framework will retain responsibility for the + * stream buffers' fences and the buffer handles; the HAL should + * not close the fences or return these buffers with + * process_capture_result. + * + * -ENODEV: If the camera device has encountered a serious error. After this + * error is returned, only the close() method can be successfully + * called by the framework. + * + */ + int (*process_capture_request)(const struct camera3_device *, + camera3_capture_request_t *request); + + /********************************************************************** + * Miscellaneous methods + */ + + /** + * get_metadata_vendor_tag_ops: + * + * Get methods to query for vendor extension metadata tag information. The + * HAL should fill in all the vendor tag operation methods, or leave ops + * unchanged if no vendor tags are defined. + * + * The definition of vendor_tag_query_ops_t can be found in + * system/media/camera/include/system/camera_metadata.h. + * + * >= CAMERA_DEVICE_API_VERSION_3_2: + * DEPRECATED. This function has been deprecated and should be set to + * NULL by the HAL. Please implement get_vendor_tag_ops in camera_common.h + * instead. + */ + void (*get_metadata_vendor_tag_ops)(const struct camera3_device*, + vendor_tag_query_ops_t* ops); + + /** + * dump: + * + * Print out debugging state for the camera device. This will be called by + * the framework when the camera service is asked for a debug dump, which + * happens when using the dumpsys tool, or when capturing a bugreport. + * + * The passed-in file descriptor can be used to write debugging text using + * dprintf() or write(). The text should be in ASCII encoding only. + * + * Performance requirements: + * + * This must be a non-blocking call. The HAL should return from this call + * in 1ms, must return from this call in 10ms. This call must avoid + * deadlocks, as it may be called at any point during camera operation. + * Any synchronization primitives used (such as mutex locks or semaphores) + * should be acquired with a timeout. + */ + void (*dump)(const struct camera3_device *, int fd); + + /** + * flush: + * + * Flush all currently in-process captures and all buffers in the pipeline + * on the given device. The framework will use this to dump all state as + * quickly as possible in order to prepare for a configure_streams() call. + * + * No buffers are required to be successfully returned, so every buffer + * held at the time of flush() (whether successfully filled or not) may be + * returned with CAMERA3_BUFFER_STATUS_ERROR. Note the HAL is still allowed + * to return valid (CAMERA3_BUFFER_STATUS_OK) buffers during this call, + * provided they are successfully filled. + * + * All requests currently in the HAL are expected to be returned as soon as + * possible. Not-in-process requests should return errors immediately. Any + * interruptible hardware blocks should be stopped, and any uninterruptible + * blocks should be waited on. + * + * flush() may be called concurrently to process_capture_request(), with the expectation that + * process_capture_request will return quickly and the request submitted in that + * process_capture_request call is treated like all other in-flight requests. Due to + * concurrency issues, it is possible that from the HAL's point of view, a + * process_capture_request() call may be started after flush has been invoked but has not + * returned yet. If such a call happens before flush() returns, the HAL should treat the new + * capture request like other in-flight pending requests (see #4 below). + * + * More specifically, the HAL must follow below requirements for various cases: + * + * 1. For captures that are too late for the HAL to cancel/stop, and will be + * completed normally by the HAL; i.e. the HAL can send shutter/notify and + * process_capture_result and buffers as normal. + * + * 2. For pending requests that have not done any processing, the HAL must call notify + * CAMERA3_MSG_ERROR_REQUEST, and return all the output buffers with + * process_capture_result in the error state (CAMERA3_BUFFER_STATUS_ERROR). + * The HAL must not place the release fence into an error state, instead, + * the release fences must be set to the acquire fences passed by the framework, + * or -1 if they have been waited on by the HAL already. This is also the path + * to follow for any captures for which the HAL already called notify() with + * CAMERA3_MSG_SHUTTER but won't be producing any metadata/valid buffers for. + * After CAMERA3_MSG_ERROR_REQUEST, for a given frame, only process_capture_results with + * buffers in CAMERA3_BUFFER_STATUS_ERROR are allowed. No further notifys or + * process_capture_result with non-null metadata is allowed. + * + * 3. For partially completed pending requests that will not have all the output + * buffers or perhaps missing metadata, the HAL should follow below: + * + * 3.1. Call notify with CAMERA3_MSG_ERROR_RESULT if some of the expected result + * metadata (i.e. one or more partial metadata) won't be available for the capture. + * + * 3.2. Call notify with CAMERA3_MSG_ERROR_BUFFER for every buffer that won't + * be produced for the capture. + * + * 3.3 Call notify with CAMERA3_MSG_SHUTTER with the capture timestamp before + * any buffers/metadata are returned with process_capture_result. + * + * 3.4 For captures that will produce some results, the HAL must not call + * CAMERA3_MSG_ERROR_REQUEST, since that indicates complete failure. + * + * 3.5. Valid buffers/metadata should be passed to the framework as normal. + * + * 3.6. Failed buffers should be returned to the framework as described for case 2. + * But failed buffers do not have to follow the strict ordering valid buffers do, + * and may be out-of-order with respect to valid buffers. For example, if buffers + * A, B, C, D, E are sent, D and E are failed, then A, E, B, D, C is an acceptable + * return order. + * + * 3.7. For fully-missing metadata, calling CAMERA3_MSG_ERROR_RESULT is sufficient, no + * need to call process_capture_result with NULL metadata or equivalent. + * + * 4. If a flush() is invoked while a process_capture_request() invocation is active, that + * process call should return as soon as possible. In addition, if a process_capture_request() + * call is made after flush() has been invoked but before flush() has returned, the + * capture request provided by the late process_capture_request call should be treated like + * a pending request in case #2 above. + * + * flush() should only return when there are no more outstanding buffers or + * requests left in the HAL. The framework may call configure_streams (as + * the HAL state is now quiesced) or may issue new requests. + * + * Note that it's sufficient to only support fully-succeeded and fully-failed result cases. + * However, it is highly desirable to support the partial failure cases as well, as it + * could help improve the flush call overall performance. + * + * Performance requirements: + * + * The HAL should return from this call in 100ms, and must return from this + * call in 1000ms. And this call must not be blocked longer than pipeline + * latency (see S7 for definition). + * + * Version information: + * + * only available if device version >= CAMERA_DEVICE_API_VERSION_3_1. + * + * Return values: + * + * 0: On a successful flush of the camera HAL. + * + * -EINVAL: If the input is malformed (the device is not valid). + * + * -ENODEV: If the camera device has encountered a serious error. After this + * error is returned, only the close() method can be successfully + * called by the framework. + */ + int (*flush)(const struct camera3_device *); + + /* reserved for future use */ + void *reserved[8]; +} camera3_device_ops_t; + +/********************************************************************** + * + * Camera device definition + * + */ +typedef struct camera3_device { + /** + * common.version must equal CAMERA_DEVICE_API_VERSION_3_0 to identify this + * device as implementing version 3.0 of the camera device HAL. + * + * Performance requirements: + * + * Camera open (common.module->common.methods->open) should return in 200ms, and must return + * in 500ms. + * Camera close (common.close) should return in 200ms, and must return in 500ms. + * + */ + hw_device_t common; + camera3_device_ops_t *ops; + void *priv; +} camera3_device_t; + +__END_DECLS + +#endif /* #ifdef ANDROID_INCLUDE_CAMERA3_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/camera_common.h b/third_party/android_hardware_libhardware/include/hardware/camera_common.h new file mode 100644 index 00000000000000..7658dd4062f39e --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/camera_common.h @@ -0,0 +1,916 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// FIXME: add well-defined names for cameras + +#ifndef ANDROID_INCLUDE_CAMERA_COMMON_H +#define ANDROID_INCLUDE_CAMERA_COMMON_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define CAMERA_HARDWARE_MODULE_ID "camera" + +/** + * Module versioning information for the Camera hardware module, based on + * camera_module_t.common.module_api_version. The two most significant hex + * digits represent the major version, and the two least significant represent + * the minor version. + * + ******************************************************************************* + * Versions: 0.X - 1.X [CAMERA_MODULE_API_VERSION_1_0] + * + * Camera modules that report these version numbers implement the initial + * camera module HAL interface. All camera devices openable through this + * module support only version 1 of the camera device HAL. The device_version + * and static_camera_characteristics fields of camera_info are not valid. Only + * the android.hardware.Camera API can be supported by this module and its + * devices. + * + ******************************************************************************* + * Version: 2.0 [CAMERA_MODULE_API_VERSION_2_0] + * + * Camera modules that report this version number implement the second version + * of the camera module HAL interface. Camera devices openable through this + * module may support either version 1.0 or version 2.0 of the camera device + * HAL interface. The device_version field of camera_info is always valid; the + * static_camera_characteristics field of camera_info is valid if the + * device_version field is 2.0 or higher. + * + ******************************************************************************* + * Version: 2.1 [CAMERA_MODULE_API_VERSION_2_1] + * + * This camera module version adds support for asynchronous callbacks to the + * framework from the camera HAL module, which is used to notify the framework + * about changes to the camera module state. Modules that provide a valid + * set_callbacks() method must report at least this version number. + * + ******************************************************************************* + * Version: 2.2 [CAMERA_MODULE_API_VERSION_2_2] + * + * This camera module version adds vendor tag support from the module, and + * deprecates the old vendor_tag_query_ops that were previously only + * accessible with a device open. + * + ******************************************************************************* + * Version: 2.3 [CAMERA_MODULE_API_VERSION_2_3] + * + * This camera module version adds open legacy camera HAL device support. + * Framework can use it to open the camera device as lower device HAL version + * HAL device if the same device can support multiple device API versions. + * The standard hardware module open call (common.methods->open) continues + * to open the camera device with the latest supported version, which is + * also the version listed in camera_info_t.device_version. + * + ******************************************************************************* + * Version: 2.4 [CAMERA_MODULE_API_VERSION_2_4] + * + * This camera module version adds below API changes: + * + * 1. Torch mode support. The framework can use it to turn on torch mode for + * any camera device that has a flash unit, without opening a camera device. The + * camera device has a higher priority accessing the flash unit than the camera + * module; opening a camera device will turn off the torch if it had been enabled + * through the module interface. When there are any resource conflicts, such as + * open() is called to open a camera device, the camera HAL module must notify the + * framework through the torch mode status callback that the torch mode has been + * turned off. + * + * 2. External camera (e.g. USB hot-plug camera) support. The API updates specify that + * the camera static info is only available when camera is connected and ready to + * use for external hot-plug cameras. Calls to get static info will be invalid + * calls when camera status is not CAMERA_DEVICE_STATUS_PRESENT. The frameworks + * will only count on device status change callbacks to manage the available external + * camera list. + * + * 3. Camera arbitration hints. This module version adds support for explicitly + * indicating the number of camera devices that can be simultaneously opened and used. + * To specify valid combinations of devices, the resource_cost and conflicting_devices + * fields should always be set in the camera_info structure returned by the + * get_camera_info call. + * + * 4. Module initialization method. This will be called by the camera service + * right after the HAL module is loaded, to allow for one-time initialization + * of the HAL. It is called before any other module methods are invoked. + */ + +/** + * Predefined macros for currently-defined version numbers + */ + +/** + * All module versions <= HARDWARE_MODULE_API_VERSION(1, 0xFF) must be treated + * as CAMERA_MODULE_API_VERSION_1_0 + */ +#define CAMERA_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define CAMERA_MODULE_API_VERSION_2_0 HARDWARE_MODULE_API_VERSION(2, 0) +#define CAMERA_MODULE_API_VERSION_2_1 HARDWARE_MODULE_API_VERSION(2, 1) +#define CAMERA_MODULE_API_VERSION_2_2 HARDWARE_MODULE_API_VERSION(2, 2) +#define CAMERA_MODULE_API_VERSION_2_3 HARDWARE_MODULE_API_VERSION(2, 3) +#define CAMERA_MODULE_API_VERSION_2_4 HARDWARE_MODULE_API_VERSION(2, 4) + +#define CAMERA_MODULE_API_VERSION_CURRENT CAMERA_MODULE_API_VERSION_2_4 + +/** + * All device versions <= HARDWARE_DEVICE_API_VERSION(1, 0xFF) must be treated + * as CAMERA_DEVICE_API_VERSION_1_0 + */ +#define CAMERA_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define CAMERA_DEVICE_API_VERSION_2_0 HARDWARE_DEVICE_API_VERSION(2, 0) +#define CAMERA_DEVICE_API_VERSION_2_1 HARDWARE_DEVICE_API_VERSION(2, 1) +#define CAMERA_DEVICE_API_VERSION_3_0 HARDWARE_DEVICE_API_VERSION(3, 0) +#define CAMERA_DEVICE_API_VERSION_3_1 HARDWARE_DEVICE_API_VERSION(3, 1) +#define CAMERA_DEVICE_API_VERSION_3_2 HARDWARE_DEVICE_API_VERSION(3, 2) +#define CAMERA_DEVICE_API_VERSION_3_3 HARDWARE_DEVICE_API_VERSION(3, 3) + +// Device version 3.3 is current, older HAL camera device versions are not +// recommended for new devices. +#define CAMERA_DEVICE_API_VERSION_CURRENT CAMERA_DEVICE_API_VERSION_3_3 + +/** + * Defined in /system/media/camera/include/system/camera_metadata.h + */ +typedef struct camera_metadata camera_metadata_t; + +typedef struct camera_info { + /** + * The direction that the camera faces to. See system/core/include/system/camera.h + * for camera facing definitions. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * It should be CAMERA_FACING_BACK or CAMERA_FACING_FRONT. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * It should be CAMERA_FACING_BACK, CAMERA_FACING_FRONT or + * CAMERA_FACING_EXTERNAL. + */ + int facing; + + /** + * The orientation of the camera image. The value is the angle that the + * camera image needs to be rotated clockwise so it shows correctly on the + * display in its natural orientation. It should be 0, 90, 180, or 270. + * + * For example, suppose a device has a naturally tall screen. The + * back-facing camera sensor is mounted in landscape. You are looking at the + * screen. If the top side of the camera sensor is aligned with the right + * edge of the screen in natural orientation, the value should be 90. If the + * top side of a front-facing camera sensor is aligned with the right of the + * screen, the value should be 270. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Valid in all camera_module versions. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * Valid if camera facing is CAMERA_FACING_BACK or CAMERA_FACING_FRONT, + * not valid if camera facing is CAMERA_FACING_EXTERNAL. + */ + int orientation; + + /** + * The value of camera_device_t.common.version. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_0: + * + * Not valid. Can be assumed to be CAMERA_DEVICE_API_VERSION_1_0. Do + * not read this field. + * + * CAMERA_MODULE_API_VERSION_2_0 or higher: + * + * Always valid + * + */ + uint32_t device_version; + + /** + * The camera's fixed characteristics, which include all static camera metadata + * specified in system/media/camera/docs/docs.html. This should be a sorted metadata + * buffer, and may not be modified or freed by the caller. The pointer should remain + * valid for the lifetime of the camera module, and values in it may not + * change after it is returned by get_camera_info(). + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_0: + * + * Not valid. Extra characteristics are not available. Do not read this + * field. + * + * CAMERA_MODULE_API_VERSION_2_0 or higher: + * + * Valid if device_version >= CAMERA_DEVICE_API_VERSION_2_0. Do not read + * otherwise. + * + */ + const camera_metadata_t *static_camera_characteristics; + + /** + * The total resource "cost" of using this camera, represented as an integer + * value in the range [0, 100] where 100 represents total usage of the shared + * resource that is the limiting bottleneck of the camera subsystem. This may + * be a very rough estimate, and is used as a hint to the camera service to + * determine when to disallow multiple applications from simultaneously + * opening different cameras advertised by the camera service. + * + * The camera service must be able to simultaneously open and use any + * combination of camera devices exposed by the HAL where the sum of + * the resource costs of these cameras is <= 100. For determining cost, + * each camera device must be assumed to be configured and operating at + * the maximally resource-consuming framerate and stream size settings + * available in the configuration settings exposed for that device through + * the camera metadata. + * + * The camera service may still attempt to simultaneously open combinations + * of camera devices with a total resource cost > 100. This may succeed or + * fail. If this succeeds, combinations of configurations that are not + * supported due to resource constraints from having multiple open devices + * should fail during the configure calls. If the total resource cost is + * <= 100, open and configure should never fail for any stream configuration + * settings or other device capabilities that would normally succeed for a + * device when it is the only open camera device. + * + * This field will be used to determine whether background applications are + * allowed to use this camera device while other applications are using other + * camera devices. Note: multiple applications will never be allowed by the + * camera service to simultaneously open the same camera device. + * + * Example use cases: + * + * Ex. 1: Camera Device 0 = Back Camera + * Camera Device 1 = Front Camera + * - Using both camera devices causes a large framerate slowdown due to + * limited ISP bandwidth. + * + * Configuration: + * + * Camera Device 0 - resource_cost = 51 + * conflicting_devices = null + * Camera Device 1 - resource_cost = 51 + * conflicting_devices = null + * + * Result: + * + * Since the sum of the resource costs is > 100, if a higher-priority + * application has either device open, no lower-priority applications will be + * allowed by the camera service to open either device. If a lower-priority + * application is using a device that a higher-priority subsequently attempts + * to open, the lower-priority application will be forced to disconnect the + * the device. + * + * If the highest-priority application chooses, it may still attempt to open + * both devices (since these devices are not listed as conflicting in the + * conflicting_devices fields), but usage of these devices may fail in the + * open or configure calls. + * + * Ex. 2: Camera Device 0 = Left Back Camera + * Camera Device 1 = Right Back Camera + * Camera Device 2 = Combined stereo camera using both right and left + * back camera sensors used by devices 0, and 1 + * Camera Device 3 = Front Camera + * - Due to do hardware constraints, up to two cameras may be open at once. The + * combined stereo camera may never be used at the same time as either of the + * two back camera devices (device 0, 1), and typically requires too much + * bandwidth to use at the same time as the front camera (device 3). + * + * Configuration: + * + * Camera Device 0 - resource_cost = 50 + * conflicting_devices = { 2 } + * Camera Device 1 - resource_cost = 50 + * conflicting_devices = { 2 } + * Camera Device 2 - resource_cost = 100 + * conflicting_devices = { 0, 1 } + * Camera Device 3 - resource_cost = 50 + * conflicting_devices = null + * + * Result: + * + * Based on the conflicting_devices fields, the camera service guarantees that + * the following sets of open devices will never be allowed: { 1, 2 }, { 0, 2 }. + * + * Based on the resource_cost fields, if a high-priority foreground application + * is using camera device 0, a background application would be allowed to open + * camera device 1 or 3 (but would be forced to disconnect it again if the + * foreground application opened another device). + * + * The highest priority application may still attempt to simultaneously open + * devices 0, 2, and 3, but the HAL may fail in open or configure calls for + * this combination. + * + * Ex. 3: Camera Device 0 = Back Camera + * Camera Device 1 = Front Camera + * Camera Device 2 = Low-power Front Camera that uses the same + * sensor as device 1, but only exposes image stream + * resolutions that can be used in low-power mode + * - Using both front cameras (device 1, 2) at the same time is impossible due + * a shared physical sensor. Using the back and "high-power" front camera + * (device 1) may be impossible for some stream configurations due to hardware + * limitations, but the "low-power" front camera option may always be used as + * it has special dedicated hardware. + * + * Configuration: + * + * Camera Device 0 - resource_cost = 100 + * conflicting_devices = null + * Camera Device 1 - resource_cost = 100 + * conflicting_devices = { 2 } + * Camera Device 2 - resource_cost = 0 + * conflicting_devices = { 1 } + * Result: + * + * Based on the conflicting_devices fields, the camera service guarantees that + * the following sets of open devices will never be allowed: { 1, 2 }. + * + * Based on the resource_cost fields, only the highest priority application + * may attempt to open both device 0 and 1 at the same time. If a higher-priority + * application is not using device 1 or 2, a low-priority background application + * may open device 2 (but will be forced to disconnect it if a higher-priority + * application subsequently opens device 1 or 2). + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Not valid. Can be assumed to be 100. Do not read this field. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * Always valid. + */ + int resource_cost; + + /** + * An array of camera device IDs represented as NULL-terminated strings + * indicating other devices that cannot be simultaneously opened while this + * camera device is in use. + * + * This field is intended to be used to indicate that this camera device + * is a composite of several other camera devices, or otherwise has + * hardware dependencies that prohibit simultaneous usage. If there are no + * dependencies, a NULL may be returned in this field to indicate this. + * + * The camera service will never simultaneously open any of the devices + * in this list while this camera device is open. + * + * The strings pointed to in this field will not be cleaned up by the camera + * service, and must remain while this device is plugged in. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Not valid. Can be assumed to be NULL. Do not read this field. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * Always valid. + */ + char** conflicting_devices; + + /** + * The length of the array given in the conflicting_devices field. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Not valid. Can be assumed to be 0. Do not read this field. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * Always valid. + */ + size_t conflicting_devices_length; + +} camera_info_t; + +/** + * camera_device_status_t: + * + * The current status of the camera device, as provided by the HAL through the + * camera_module_callbacks.camera_device_status_change() call. + * + * At module load time, the framework will assume all camera devices are in the + * CAMERA_DEVICE_STATUS_PRESENT state. The HAL should invoke + * camera_module_callbacks::camera_device_status_change to inform the framework + * of any initially NOT_PRESENT devices. + * + * Allowed transitions: + * PRESENT -> NOT_PRESENT + * NOT_PRESENT -> ENUMERATING + * NOT_PRESENT -> PRESENT + * ENUMERATING -> PRESENT + * ENUMERATING -> NOT_PRESENT + */ +typedef enum camera_device_status { + /** + * The camera device is not currently connected, and opening it will return + * failure. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Calls to get_camera_info must still succeed, and provide the same information + * it would if the camera were connected. + * + * CAMERA_MODULE_API_VERSION_2_4: + * + * The camera device at this status must return -EINVAL for get_camera_info call, + * as the device is not connected. + */ + CAMERA_DEVICE_STATUS_NOT_PRESENT = 0, + + /** + * The camera device is connected, and opening it will succeed. + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * The information returned by get_camera_info cannot change due to this status + * change. By default, the framework will assume all devices are in this state. + * + * CAMERA_MODULE_API_VERSION_2_4: + * + * The information returned by get_camera_info will become valid after a device's + * status changes to this. By default, the framework will assume all devices are in + * this state. + */ + CAMERA_DEVICE_STATUS_PRESENT = 1, + + /** + * The camera device is connected, but it is undergoing an enumeration and + * so opening the device will return -EBUSY. + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * Calls to get_camera_info must still succeed, as if the camera was in the + * PRESENT status. + * + * CAMERA_MODULE_API_VERSION_2_4: + * + * The camera device at this status must return -EINVAL for get_camera_info for call, + * as the device is not ready. + */ + CAMERA_DEVICE_STATUS_ENUMERATING = 2, + +} camera_device_status_t; + +/** + * torch_mode_status_t: + * + * The current status of the torch mode, as provided by the HAL through the + * camera_module_callbacks.torch_mode_status_change() call. + * + * The torch mode status of a camera device is applicable only when the camera + * device is present. The framework will not call set_torch_mode() to turn on + * torch mode of a camera device if the camera device is not present. At module + * load time, the framework will assume torch modes are in the + * TORCH_MODE_STATUS_AVAILABLE_OFF state if the camera device is present and + * android.flash.info.available is reported as true via get_camera_info() call. + * + * The behaviors of the camera HAL module that the framework expects in the + * following situations when a camera device's status changes: + * 1. A previously-disconnected camera device becomes connected. + * After camera_module_callbacks::camera_device_status_change() is invoked + * to inform the framework that the camera device is present, the framework + * will assume the camera device's torch mode is in + * TORCH_MODE_STATUS_AVAILABLE_OFF state. The camera HAL module does not need + * to invoke camera_module_callbacks::torch_mode_status_change() unless the + * flash unit is unavailable to use by set_torch_mode(). + * + * 2. A previously-connected camera becomes disconnected. + * After camera_module_callbacks::camera_device_status_change() is invoked + * to inform the framework that the camera device is not present, the + * framework will not call set_torch_mode() for the disconnected camera + * device until its flash unit becomes available again. The camera HAL + * module does not need to invoke + * camera_module_callbacks::torch_mode_status_change() separately to inform + * that the flash unit has become unavailable. + * + * 3. open() is called to open a camera device. + * The camera HAL module must invoke + * camera_module_callbacks::torch_mode_status_change() for all flash units + * that have entered TORCH_MODE_STATUS_NOT_AVAILABLE state and can not be + * turned on by calling set_torch_mode() anymore due to this open() call. + * open() must not trigger TORCH_MODE_STATUS_AVAILABLE_OFF before + * TORCH_MODE_STATUS_NOT_AVAILABLE for all flash units that have become + * unavailable. + * + * 4. close() is called to close a camera device. + * The camera HAL module must invoke + * camera_module_callbacks::torch_mode_status_change() for all flash units + * that have entered TORCH_MODE_STATUS_AVAILABLE_OFF state and can be turned + * on by calling set_torch_mode() again because of enough resources freed + * up by this close() call. + * + * Note that the framework calling set_torch_mode() successfully must trigger + * TORCH_MODE_STATUS_AVAILABLE_OFF or TORCH_MODE_STATUS_AVAILABLE_ON callback + * for the given camera device. Additionally it must trigger + * TORCH_MODE_STATUS_AVAILABLE_OFF callbacks for other previously-on torch + * modes if HAL cannot keep multiple torch modes on simultaneously. + */ +typedef enum torch_mode_status { + + /** + * The flash unit is no longer available and the torch mode can not be + * turned on by calling set_torch_mode(). If the torch mode is on, it + * will be turned off by HAL before HAL calls torch_mode_status_change(). + */ + TORCH_MODE_STATUS_NOT_AVAILABLE = 0, + + /** + * A torch mode has become off and available to be turned on via + * set_torch_mode(). This may happen in the following + * cases: + * 1. After the resources to turn on the torch mode have become available. + * 2. After set_torch_mode() is called to turn off the torch mode. + * 3. After the framework turned on the torch mode of some other camera + * device and HAL had to turn off the torch modes of any camera devices + * that were previously on. + */ + TORCH_MODE_STATUS_AVAILABLE_OFF = 1, + + /** + * A torch mode has become on and available to be turned off via + * set_torch_mode(). This can happen only after set_torch_mode() is called + * to turn on the torch mode. + */ + TORCH_MODE_STATUS_AVAILABLE_ON = 2, + +} torch_mode_status_t; + +/** + * Callback functions for the camera HAL module to use to inform the framework + * of changes to the camera subsystem. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * Each callback is called only by HAL modules implementing the indicated + * version or higher of the HAL module API interface. + * + * CAMERA_MODULE_API_VERSION_2_1: + * camera_device_status_change() + * + * CAMERA_MODULE_API_VERSION_2_4: + * torch_mode_status_change() + + */ +typedef struct camera_module_callbacks { + + /** + * camera_device_status_change: + * + * Callback to the framework to indicate that the state of a specific camera + * device has changed. At module load time, the framework will assume all + * camera devices are in the CAMERA_DEVICE_STATUS_PRESENT state. The HAL + * must call this method to inform the framework of any initially + * NOT_PRESENT devices. + * + * This callback is added for CAMERA_MODULE_API_VERSION_2_1. + * + * camera_module_callbacks: The instance of camera_module_callbacks_t passed + * to the module with set_callbacks. + * + * camera_id: The ID of the camera device that has a new status. + * + * new_status: The new status code, one of the camera_device_status_t enums, + * or a platform-specific status. + * + */ + void (*camera_device_status_change)(const struct camera_module_callbacks*, + int camera_id, + int new_status); + + /** + * torch_mode_status_change: + * + * Callback to the framework to indicate that the state of the torch mode + * of the flash unit associated with a specific camera device has changed. + * At module load time, the framework will assume the torch modes are in + * the TORCH_MODE_STATUS_AVAILABLE_OFF state if android.flash.info.available + * is reported as true via get_camera_info() call. + * + * This callback is added for CAMERA_MODULE_API_VERSION_2_4. + * + * camera_module_callbacks: The instance of camera_module_callbacks_t + * passed to the module with set_callbacks. + * + * camera_id: The ID of camera device whose flash unit has a new torch mode + * status. + * + * new_status: The new status code, one of the torch_mode_status_t enums. + */ + void (*torch_mode_status_change)(const struct camera_module_callbacks*, + const char* camera_id, + int new_status); + + +} camera_module_callbacks_t; + +typedef struct camera_module { + /** + * Common methods of the camera module. This *must* be the first member of + * camera_module as users of this structure will cast a hw_module_t to + * camera_module pointer in contexts where it's known the hw_module_t + * references a camera_module. + * + * The return values for common.methods->open for camera_module are: + * + * 0: On a successful open of the camera device. + * + * -ENODEV: The camera device cannot be opened due to an internal + * error. + * + * -EINVAL: The input arguments are invalid, i.e. the id is invalid, + * and/or the module is invalid. + * + * -EBUSY: The camera device was already opened for this camera id + * (by using this method or open_legacy), + * regardless of the device HAL version it was opened as. + * + * -EUSERS: The maximal number of camera devices that can be + * opened concurrently were opened already, either by + * this method or the open_legacy method. + * + * All other return values from common.methods->open will be treated as + * -ENODEV. + */ + hw_module_t common; + + /** + * get_number_of_cameras: + * + * Returns the number of camera devices accessible through the camera + * module. The camera devices are numbered 0 through N-1, where N is the + * value returned by this call. The name of the camera device for open() is + * simply the number converted to a string. That is, "0" for camera ID 0, + * "1" for camera ID 1. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_3 or lower: + * + * The value here must be static, and cannot change after the first call + * to this method. + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * The value here must be static, and must count only built-in cameras, + * which have CAMERA_FACING_BACK or CAMERA_FACING_FRONT camera facing values + * (camera_info.facing). The HAL must not include the external cameras + * (camera_info.facing == CAMERA_FACING_EXTERNAL) into the return value + * of this call. Frameworks will use camera_device_status_change callback + * to manage number of external cameras. + */ + int (*get_number_of_cameras)(void); + + /** + * get_camera_info: + * + * Return the static camera information for a given camera device. This + * information may not change for a camera device. + * + * Return values: + * + * 0: On a successful operation + * + * -ENODEV: The information cannot be provided due to an internal + * error. + * + * -EINVAL: The input arguments are invalid, i.e. the id is invalid, + * and/or the module is invalid. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_2_4 or higher: + * + * When a camera is disconnected, its camera id becomes invalid. Calling this + * this method with this invalid camera id will get -EINVAL and NULL camera + * static metadata (camera_info.static_camera_characteristics). + */ + int (*get_camera_info)(int camera_id, struct camera_info *info); + + /** + * set_callbacks: + * + * Provide callback function pointers to the HAL module to inform framework + * of asynchronous camera module events. The framework will call this + * function once after initial camera HAL module load, after the + * get_number_of_cameras() method is called for the first time, and before + * any other calls to the module. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_0, CAMERA_MODULE_API_VERSION_2_0: + * + * Not provided by HAL module. Framework may not call this function. + * + * CAMERA_MODULE_API_VERSION_2_1: + * + * Valid to be called by the framework. + * + * Return values: + * + * 0: On a successful operation + * + * -ENODEV: The operation cannot be completed due to an internal + * error. + * + * -EINVAL: The input arguments are invalid, i.e. the callbacks are + * null + */ + int (*set_callbacks)(const camera_module_callbacks_t *callbacks); + + /** + * get_vendor_tag_ops: + * + * Get methods to query for vendor extension metadata tag information. The + * HAL should fill in all the vendor tag operation methods, or leave ops + * unchanged if no vendor tags are defined. + * + * The vendor_tag_ops structure used here is defined in: + * system/media/camera/include/system/vendor_tags.h + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_x/2_0/2_1: + * Not provided by HAL module. Framework may not call this function. + * + * CAMERA_MODULE_API_VERSION_2_2: + * Valid to be called by the framework. + */ + void (*get_vendor_tag_ops)(vendor_tag_ops_t* ops); + + /** + * open_legacy: + * + * Open a specific legacy camera HAL device if multiple device HAL API + * versions are supported by this camera HAL module. For example, if the + * camera module supports both CAMERA_DEVICE_API_VERSION_1_0 and + * CAMERA_DEVICE_API_VERSION_3_2 device API for the same camera id, + * framework can call this function to open the camera device as + * CAMERA_DEVICE_API_VERSION_1_0 device. + * + * This is an optional method. A Camera HAL module does not need to support + * more than one device HAL version per device, and such modules may return + * -ENOSYS for all calls to this method. For all older HAL device API + * versions that are not supported, it may return -EOPNOTSUPP. When above + * cases occur, The normal open() method (common.methods->open) will be + * used by the framework instead. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_x/2_0/2_1/2_2: + * Not provided by HAL module. Framework will not call this function. + * + * CAMERA_MODULE_API_VERSION_2_3: + * Valid to be called by the framework. + * + * Return values: + * + * 0: On a successful open of the camera device. + * + * -ENOSYS This method is not supported. + * + * -EOPNOTSUPP: The requested HAL version is not supported by this method. + * + * -EINVAL: The input arguments are invalid, i.e. the id is invalid, + * and/or the module is invalid. + * + * -EBUSY: The camera device was already opened for this camera id + * (by using this method or common.methods->open method), + * regardless of the device HAL version it was opened as. + * + * -EUSERS: The maximal number of camera devices that can be + * opened concurrently were opened already, either by + * this method or common.methods->open method. + */ + int (*open_legacy)(const struct hw_module_t* module, const char* id, + uint32_t halVersion, struct hw_device_t** device); + + /** + * set_torch_mode: + * + * Turn on or off the torch mode of the flash unit associated with a given + * camera ID. If the operation is successful, HAL must notify the framework + * torch state by invoking + * camera_module_callbacks.torch_mode_status_change() with the new state. + * + * The camera device has a higher priority accessing the flash unit. When + * there are any resource conflicts, such as open() is called to open a + * camera device, HAL module must notify the framework through + * camera_module_callbacks.torch_mode_status_change() that the + * torch mode has been turned off and the torch mode state has become + * TORCH_MODE_STATUS_NOT_AVAILABLE. When resources to turn on torch mode + * become available again, HAL module must notify the framework through + * camera_module_callbacks.torch_mode_status_change() that the torch mode + * state has become TORCH_MODE_STATUS_AVAILABLE_OFF for set_torch_mode() to + * be called. + * + * When the framework calls set_torch_mode() to turn on the torch mode of a + * flash unit, if HAL cannot keep multiple torch modes on simultaneously, + * HAL should turn off the torch mode that was turned on by + * a previous set_torch_mode() call and notify the framework that the torch + * mode state of that flash unit has become TORCH_MODE_STATUS_AVAILABLE_OFF. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_x/2_0/2_1/2_2/2_3: + * Not provided by HAL module. Framework will not call this function. + * + * CAMERA_MODULE_API_VERSION_2_4: + * Valid to be called by the framework. + * + * Return values: + * + * 0: On a successful operation. + * + * -ENOSYS: The camera device does not support this operation. It is + * returned if and only if android.flash.info.available is + * false. + * + * -EBUSY: The camera device is already in use. + * + * -EUSERS: The resources needed to turn on the torch mode are not + * available, typically because other camera devices are + * holding the resources to make using the flash unit not + * possible. + * + * -EINVAL: camera_id is invalid. + * + */ + int (*set_torch_mode)(const char* camera_id, bool enabled); + + /** + * init: + * + * This method is called by the camera service before any other methods + * are invoked, right after the camera HAL library has been successfully + * loaded. It may be left as NULL by the HAL module, if no initialization + * in needed. + * + * It can be used by HAL implementations to perform initialization and + * other one-time operations. + * + * Version information (based on camera_module_t.common.module_api_version): + * + * CAMERA_MODULE_API_VERSION_1_x/2_0/2_1/2_2/2_3: + * Not provided by HAL module. Framework will not call this function. + * + * CAMERA_MODULE_API_VERSION_2_4: + * If not NULL, will always be called by the framework once after the HAL + * module is loaded, before any other HAL module method is called. + * + * Return values: + * + * 0: On a successful operation. + * + * -ENODEV: Initialization cannot be completed due to an internal + * error. The HAL must be assumed to be in a nonfunctional + * state. + * + */ + int (*init)(); + + /* reserved for future use */ + void* reserved[5]; +} camera_module_t; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_CAMERA_COMMON_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/consumerir.h b/third_party/android_hardware_libhardware/include/hardware/consumerir.h new file mode 100644 index 00000000000000..15334c1111637a --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/consumerir.h @@ -0,0 +1,92 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_CONSUMERIR_H +#define ANDROID_INCLUDE_HARDWARE_CONSUMERIR_H + +#include +#include +#include +#include + +#define CONSUMERIR_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define CONSUMERIR_HARDWARE_MODULE_ID "consumerir" +#define CONSUMERIR_TRANSMITTER "transmitter" + +typedef struct consumerir_freq_range { + int min; + int max; +} consumerir_freq_range_t; + +typedef struct consumerir_module { + /** + * Common methods of the consumer IR module. This *must* be the first member of + * consumerir_module as users of this structure will cast a hw_module_t to + * consumerir_module pointer in contexts where it's known the hw_module_t references a + * consumerir_module. + */ + struct hw_module_t common; +} consumerir_module_t; + +typedef struct consumerir_device { + /** + * Common methods of the consumer IR device. This *must* be the first member of + * consumerir_device as users of this structure will cast a hw_device_t to + * consumerir_device pointer in contexts where it's known the hw_device_t references a + * consumerir_device. + */ + struct hw_device_t common; + + /* + * (*transmit)() is called to by the ConsumerIrService to send an IR pattern + * at a given carrier_freq. + * + * The pattern is alternating series of carrier on and off periods measured in + * microseconds. The carrier should be turned off at the end of a transmit + * even if there are and odd number of entries in the pattern array. + * + * This call should return when the transmit is complete or encounters an error. + * + * returns: 0 on success. A negative error code on error. + */ + int (*transmit)(struct consumerir_device *dev, int carrier_freq, + const int pattern[], int pattern_len); + + /* + * (*get_num_carrier_freqs)() is called by the ConsumerIrService to get the + * number of carrier freqs to allocate space for, which is then filled by + * a subsequent call to (*get_carrier_freqs)(). + * + * returns: the number of ranges on success. A negative error code on error. + */ + int (*get_num_carrier_freqs)(struct consumerir_device *dev); + + /* + * (*get_carrier_freqs)() is called by the ConsumerIrService to enumerate + * which frequencies the IR transmitter supports. The HAL implementation + * should fill an array of consumerir_freq_range structs with the + * appropriate values for the transmitter, up to len elements. + * + * returns: the number of ranges on success. A negative error code on error. + */ + int (*get_carrier_freqs)(struct consumerir_device *dev, + size_t len, consumerir_freq_range_t *ranges); + + /* Reserved for future use. Must be NULL. */ + void* reserved[8 - 3]; +} consumerir_device_t; + +#endif /* ANDROID_INCLUDE_HARDWARE_CONSUMERIR_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/display_defs.h b/third_party/android_hardware_libhardware/include/hardware/display_defs.h new file mode 100644 index 00000000000000..669ef78c4e96be --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/display_defs.h @@ -0,0 +1,67 @@ +/* Copyright (c) 2014-2015, The Linux Foundation. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are + * met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of The Linux Foundation nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS + * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR + * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE + * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN + * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ANDROID_INCLUDE_DISPLAY_DEFS_H +#define ANDROID_INCLUDE_DISPLAY_DEFS_H + +#include +#include + +#include + +__BEGIN_DECLS + +/* Will need to update below enums if hwcomposer_defs.h is updated */ + +/* Extended events for hwc_methods::eventControl() */ +enum { + HWC_EVENT_ORIENTATION = HWC_EVENT_VSYNC + 1 +}; + + +/* Extended hwc_layer_t::compositionType values */ +enum { + /* this layer will be handled in the HWC, using a blit engine */ + HWC_BLIT = 0xFF +}; + +/* Extended hwc_layer_t::flags values + * Flags are set by SurfaceFlinger and read by the HAL + */ +enum { + /* + * HWC_SCREENSHOT_ANIMATOR_LAYER is set by surfaceflinger to indicate + * that this layer is a screenshot animating layer. HWC uses this + * info to disable rotation animation on External Display + */ + HWC_SCREENSHOT_ANIMATOR_LAYER = 0x00000004 +}; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_DISPLAY_DEFS_H*/ diff --git a/third_party/android_hardware_libhardware/include/hardware/fb.h b/third_party/android_hardware_libhardware/include/hardware/fb.h new file mode 100644 index 00000000000000..9df94165b9b1bf --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/fb.h @@ -0,0 +1,173 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_FB_INTERFACE_H +#define ANDROID_FB_INTERFACE_H + +#include +#include +#include + +#include + +#include + +__BEGIN_DECLS + +#define GRALLOC_HARDWARE_FB0 "fb0" + +/*****************************************************************************/ + + +/*****************************************************************************/ + +typedef struct framebuffer_device_t { + /** + * Common methods of the framebuffer device. This *must* be the first member of + * framebuffer_device_t as users of this structure will cast a hw_device_t to + * framebuffer_device_t pointer in contexts where it's known the hw_device_t references a + * framebuffer_device_t. + */ + struct hw_device_t common; + + /* flags describing some attributes of the framebuffer */ + const uint32_t flags; + + /* dimensions of the framebuffer in pixels */ + const uint32_t width; + const uint32_t height; + + /* frambuffer stride in pixels */ + const int stride; + + /* framebuffer pixel format */ + const int format; + + /* resolution of the framebuffer's display panel in pixel per inch*/ + const float xdpi; + const float ydpi; + + /* framebuffer's display panel refresh rate in frames per second */ + const float fps; + + /* min swap interval supported by this framebuffer */ + const int minSwapInterval; + + /* max swap interval supported by this framebuffer */ + const int maxSwapInterval; + + /* Number of framebuffers supported*/ + const int numFramebuffers; + + int reserved[7]; + + /* + * requests a specific swap-interval (same definition than EGL) + * + * Returns 0 on success or -errno on error. + */ + int (*setSwapInterval)(struct framebuffer_device_t* window, + int interval); + + /* + * This hook is OPTIONAL. + * + * It is non NULL If the framebuffer driver supports "update-on-demand" + * and the given rectangle is the area of the screen that gets + * updated during (*post)(). + * + * This is useful on devices that are able to DMA only a portion of + * the screen to the display panel, upon demand -- as opposed to + * constantly refreshing the panel 60 times per second, for instance. + * + * Only the area defined by this rectangle is guaranteed to be valid, that + * is, the driver is not allowed to post anything outside of this + * rectangle. + * + * The rectangle evaluated during (*post)() and specifies which area + * of the buffer passed in (*post)() shall to be posted. + * + * return -EINVAL if width or height <=0, or if left or top < 0 + */ + int (*setUpdateRect)(struct framebuffer_device_t* window, + int left, int top, int width, int height); + + /* + * Post to the display (display it on the screen) + * The buffer must have been allocated with the + * GRALLOC_USAGE_HW_FB usage flag. + * buffer must be the same width and height as the display and must NOT + * be locked. + * + * The buffer is shown during the next VSYNC. + * + * If the same buffer is posted again (possibly after some other buffer), + * post() will block until the the first post is completed. + * + * Internally, post() is expected to lock the buffer so that a + * subsequent call to gralloc_module_t::(*lock)() with USAGE_RENDER or + * USAGE_*_WRITE will block until it is safe; that is typically once this + * buffer is shown and another buffer has been posted. + * + * Returns 0 on success or -errno on error. + */ + int (*post)(struct framebuffer_device_t* dev, buffer_handle_t buffer); + + + /* + * The (*compositionComplete)() method must be called after the + * compositor has finished issuing GL commands for client buffers. + */ + + int (*compositionComplete)(struct framebuffer_device_t* dev); + + /* + * This hook is OPTIONAL. + * + * If non NULL it will be caused by SurfaceFlinger on dumpsys + */ + void (*dump)(struct framebuffer_device_t* dev, char *buff, int buff_len); + + /* + * (*enableScreen)() is used to either blank (enable=0) or + * unblank (enable=1) the screen this framebuffer is attached to. + * + * Returns 0 on success or -errno on error. + */ + int (*enableScreen)(struct framebuffer_device_t* dev, int enable); + + void* reserved_proc[6]; + +} framebuffer_device_t; + + +/** convenience API for opening and closing a supported device */ + +static inline int framebuffer_open(const struct hw_module_t* module, + struct framebuffer_device_t** device) { + return module->methods->open(module, + GRALLOC_HARDWARE_FB0, (struct hw_device_t**)device); +} + +static inline int framebuffer_close(struct framebuffer_device_t* device) { + return device->common.close(&device->common); +} + + +__END_DECLS + +#endif // ANDROID_FB_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/fingerprint.h b/third_party/android_hardware_libhardware/include/hardware/fingerprint.h new file mode 100644 index 00000000000000..ac88c10322c5c9 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/fingerprint.h @@ -0,0 +1,266 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_FINGERPRINT_H +#define ANDROID_INCLUDE_HARDWARE_FINGERPRINT_H + +#include + +#define FINGERPRINT_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define FINGERPRINT_MODULE_API_VERSION_2_0 HARDWARE_MODULE_API_VERSION(2, 0) +#define FINGERPRINT_HARDWARE_MODULE_ID "fingerprint" + +typedef enum fingerprint_msg_type { + FINGERPRINT_ERROR = -1, + FINGERPRINT_ACQUIRED = 1, + FINGERPRINT_TEMPLATE_ENROLLING = 3, + FINGERPRINT_TEMPLATE_REMOVED = 4, + FINGERPRINT_AUTHENTICATED = 5 +} fingerprint_msg_type_t; + +/* + * Fingerprint errors are meant to tell the framework to terminate the current operation and ask + * for the user to correct the situation. These will almost always result in messaging and user + * interaction to correct the problem. + * + * For example, FINGERPRINT_ERROR_CANCELED should follow any acquisition message that results in + * a situation where the current operation can't continue without user interaction. For example, + * if the sensor is dirty during enrollment and no further enrollment progress can be made, + * send FINGERPRINT_ACQUIRED_IMAGER_DIRTY followed by FINGERPRINT_ERROR_CANCELED. + */ +typedef enum fingerprint_error { + FINGERPRINT_ERROR_HW_UNAVAILABLE = 1, /* The hardware has an error that can't be resolved. */ + FINGERPRINT_ERROR_UNABLE_TO_PROCESS = 2, /* Bad data; operation can't continue */ + FINGERPRINT_ERROR_TIMEOUT = 3, /* The operation has timed out waiting for user input. */ + FINGERPRINT_ERROR_NO_SPACE = 4, /* No space available to store a template */ + FINGERPRINT_ERROR_CANCELED = 5, /* The current operation can't proceed. See above. */ + FINGERPRINT_ERROR_UNABLE_TO_REMOVE = 6, /* fingerprint with given id can't be removed */ + FINGERPRINT_ERROR_VENDOR_BASE = 1000 /* vendor-specific error messages start here */ +} fingerprint_error_t; + +/* + * Fingerprint acquisition info is meant as feedback for the current operation. Anything but + * FINGERPRINT_ACQUIRED_GOOD will be shown to the user as feedback on how to take action on the + * current operation. For example, FINGERPRINT_ACQUIRED_IMAGER_DIRTY can be used to tell the user + * to clean the sensor. If this will cause the current operation to fail, an additional + * FINGERPRINT_ERROR_CANCELED can be sent to stop the operation in progress (e.g. enrollment). + * In general, these messages will result in a "Try again" message. + */ +typedef enum fingerprint_acquired_info { + FINGERPRINT_ACQUIRED_GOOD = 0, + FINGERPRINT_ACQUIRED_PARTIAL = 1, /* sensor needs more data, i.e. longer swipe. */ + FINGERPRINT_ACQUIRED_INSUFFICIENT = 2, /* image doesn't contain enough detail for recognition*/ + FINGERPRINT_ACQUIRED_IMAGER_DIRTY = 3, /* sensor needs to be cleaned */ + FINGERPRINT_ACQUIRED_TOO_SLOW = 4, /* mostly swipe-type sensors; not enough data collected */ + FINGERPRINT_ACQUIRED_TOO_FAST = 5, /* for swipe and area sensors; tell user to slow down*/ + FINGERPRINT_ACQUIRED_VENDOR_BASE = 1000 /* vendor-specific acquisition messages start here */ +} fingerprint_acquired_info_t; + +typedef struct fingerprint_finger_id { + uint32_t gid; + uint32_t fid; +} fingerprint_finger_id_t; + +typedef struct fingerprint_enroll { + fingerprint_finger_id_t finger; + /* samples_remaining goes from N (no data collected, but N scans needed) + * to 0 (no more data is needed to build a template). */ + uint32_t samples_remaining; + uint64_t msg; /* Vendor specific message. Used for user guidance */ +} fingerprint_enroll_t; + +typedef struct fingerprint_removed { + fingerprint_finger_id_t finger; +} fingerprint_removed_t; + +typedef struct fingerprint_acquired { + fingerprint_acquired_info_t acquired_info; /* information about the image */ +} fingerprint_acquired_t; + +typedef struct fingerprint_authenticated { + fingerprint_finger_id_t finger; + hw_auth_token_t hat; +} fingerprint_authenticated_t; + +typedef struct fingerprint_msg { + fingerprint_msg_type_t type; + union { + fingerprint_error_t error; + fingerprint_enroll_t enroll; + fingerprint_removed_t removed; + fingerprint_acquired_t acquired; + fingerprint_authenticated_t authenticated; + } data; +} fingerprint_msg_t; + +/* Callback function type */ +typedef void (*fingerprint_notify_t)(const fingerprint_msg_t *msg); + +/* Synchronous operation */ +typedef struct fingerprint_device { + /** + * Common methods of the fingerprint device. This *must* be the first member + * of fingerprint_device as users of this structure will cast a hw_device_t + * to fingerprint_device pointer in contexts where it's known + * the hw_device_t references a fingerprint_device. + */ + struct hw_device_t common; + + /* + * Client provided callback function to receive notifications. + * Do not set by hand, use the function above instead. + */ + fingerprint_notify_t notify; + + /* + * Set notification callback: + * Registers a user function that would receive notifications from the HAL + * The call will block if the HAL state machine is in busy state until HAL + * leaves the busy state. + * + * Function return: 0 if callback function is successfuly registered + * or a negative number in case of error, generally from the errno.h set. + */ + int (*set_notify)(struct fingerprint_device *dev, fingerprint_notify_t notify); + + /* + * Fingerprint pre-enroll enroll request: + * Generates a unique token to upper layers to indicate the start of an enrollment transaction. + * This token will be wrapped by security for verification and passed to enroll() for + * verification before enrollment will be allowed. This is to ensure adding a new fingerprint + * template was preceded by some kind of credential confirmation (e.g. device password). + * + * Function return: 0 if function failed + * otherwise, a uint64_t of token + */ + uint64_t (*pre_enroll)(struct fingerprint_device *dev); + + /* + * Fingerprint enroll request: + * Switches the HAL state machine to collect and store a new fingerprint + * template. Switches back as soon as enroll is complete + * (fingerprint_msg.type == FINGERPRINT_TEMPLATE_ENROLLING && + * fingerprint_msg.data.enroll.samples_remaining == 0) + * or after timeout_sec seconds. + * The fingerprint template will be assigned to the group gid. User has a choice + * to supply the gid or set it to 0 in which case a unique group id will be generated. + * + * Function return: 0 if enrollment process can be successfully started + * or a negative number in case of error, generally from the errno.h set. + * A notify() function may be called indicating the error condition. + */ + int (*enroll)(struct fingerprint_device *dev, const hw_auth_token_t *hat, + uint32_t gid, uint32_t timeout_sec); + + /* + * Finishes the enroll operation and invalidates the pre_enroll() generated challenge. + * This will be called at the end of a multi-finger enrollment session to indicate + * that no more fingers will be added. + * + * Function return: 0 if the request is accepted + * or a negative number in case of error, generally from the errno.h set. + */ + int (*post_enroll)(struct fingerprint_device *dev); + + /* + * get_authenticator_id: + * Returns a token associated with the current fingerprint set. This value will + * change whenever a new fingerprint is enrolled, thus creating a new fingerprint + * set. + * + * Function return: current authenticator id or 0 if function failed. + */ + uint64_t (*get_authenticator_id)(struct fingerprint_device *dev); + + /* + * Cancel pending enroll or authenticate, sending FINGERPRINT_ERROR_CANCELED + * to all running clients. Switches the HAL state machine back to the idle state. + * Unlike enroll_done() doesn't invalidate the pre_enroll() challenge. + * + * Function return: 0 if cancel request is accepted + * or a negative number in case of error, generally from the errno.h set. + */ + int (*cancel)(struct fingerprint_device *dev); + + /* + * Enumerate all the fingerprint templates found in the directory set by + * set_active_group() + * This is a synchronous call. The function takes: + * - A pointer to an array of fingerprint_finger_id_t. + * - The size of the array provided, in fingerprint_finger_id_t elements. + * Max_size is a bi-directional parameter and returns the actual number + * of elements copied to the caller supplied array. + * In the absence of errors the function returns the total number of templates + * in the user directory. + * If the caller has no good guess on the size of the array he should call this + * function witn *max_size == 0 and use the return value for the array allocation. + * The caller of this function has a complete list of the templates when *max_size + * is the same as the function return. + * + * Function return: Total number of fingerprint templates in the current storage directory. + * or a negative number in case of error, generally from the errno.h set. + */ + int (*enumerate)(struct fingerprint_device *dev, fingerprint_finger_id_t *results, + uint32_t *max_size); + + /* + * Fingerprint remove request: + * Deletes a fingerprint template. + * Works only within a path set by set_active_group(). + * notify() will be called with details on the template deleted. + * fingerprint_msg.type == FINGERPRINT_TEMPLATE_REMOVED and + * fingerprint_msg.data.removed.id indicating the template id removed. + * + * Function return: 0 if fingerprint template(s) can be successfully deleted + * or a negative number in case of error, generally from the errno.h set. + */ + int (*remove)(struct fingerprint_device *dev, uint32_t gid, uint32_t fid); + + /* + * Restricts the HAL operation to a set of fingerprints belonging to a + * group provided. + * The caller must provide a path to a storage location within the user's + * data directory. + * + * Function return: 0 on success + * or a negative number in case of error, generally from the errno.h set. + */ + int (*set_active_group)(struct fingerprint_device *dev, uint32_t gid, + const char *store_path); + + /* + * Authenticates an operation identifed by operation_id + * + * Function return: 0 on success + * or a negative number in case of error, generally from the errno.h set. + */ + int (*authenticate)(struct fingerprint_device *dev, uint64_t operation_id, uint32_t gid); + + /* Reserved for backward binary compatibility */ + void *reserved[4]; +} fingerprint_device_t; + +typedef struct fingerprint_module { + /** + * Common methods of the fingerprint module. This *must* be the first member + * of fingerprint_module as users of this structure will cast a hw_module_t + * to fingerprint_module pointer in contexts where it's known + * the hw_module_t references a fingerprint_module. + */ + struct hw_module_t common; +} fingerprint_module_t; + +#endif /* ANDROID_INCLUDE_HARDWARE_FINGERPRINT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/fused_location.h b/third_party/android_hardware_libhardware/include/hardware/fused_location.h new file mode 100644 index 00000000000000..73360a12a1289b --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/fused_location.h @@ -0,0 +1,825 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_FUSED_LOCATION_H +#define ANDROID_INCLUDE_HARDWARE_FUSED_LOCATION_H + +#include + + +/** + * This header file defines the interface of the Fused Location Provider. + * Fused Location Provider is designed to fuse data from various sources + * like GPS, Wifi, Cell, Sensors, Bluetooth etc to provide a fused location to the + * upper layers. The advantage of doing fusion in hardware is power savings. + * The goal is to do this without waking up the AP to get additional data. + * The software implementation of FLP will decide when to use + * the hardware fused location. Other location features like geofencing will + * also be implemented using fusion in hardware. + */ +__BEGIN_DECLS + +#define FLP_HEADER_VERSION 1 +#define FLP_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) +#define FLP_DEVICE_API_VERSION_0_1 HARDWARE_DEVICE_API_VERSION_2(0, 1, FLP_HEADER_VERSION) + +/** + * The id of this module + */ +#define FUSED_LOCATION_HARDWARE_MODULE_ID "flp" + +/** + * Name for the FLP location interface + */ +#define FLP_LOCATION_INTERFACE "flp_location" + +/** + * Name for the FLP location interface + */ +#define FLP_DIAGNOSTIC_INTERFACE "flp_diagnostic" + +/** + * Name for the FLP_Geofencing interface. + */ +#define FLP_GEOFENCING_INTERFACE "flp_geofencing" + +/** + * Name for the FLP_device context interface. + */ +#define FLP_DEVICE_CONTEXT_INTERFACE "flp_device_context" + +/** + * Constants to indicate the various subsystems + * that will be used. + */ +#define FLP_TECH_MASK_GNSS (1U<<0) +#define FLP_TECH_MASK_WIFI (1U<<1) +#define FLP_TECH_MASK_SENSORS (1U<<2) +#define FLP_TECH_MASK_CELL (1U<<3) +#define FLP_TECH_MASK_BLUETOOTH (1U<<4) + +/** + * Set when your implementation can produce GNNS-derived locations, + * for use with flp_capabilities_callback. + * + * GNNS is a required capability for a particular feature to be used + * (batching or geofencing). If not supported that particular feature + * won't be used by the upper layer. + */ +#define CAPABILITY_GNSS (1U<<0) +/** + * Set when your implementation can produce WiFi-derived locations, for + * use with flp_capabilities_callback. + */ +#define CAPABILITY_WIFI (1U<<1) +/** + * Set when your implementation can produce cell-derived locations, for + * use with flp_capabilities_callback. + */ +#define CAPABILITY_CELL (1U<<3) + +/** + * Status to return in flp_status_callback when your implementation transitions + * from being unsuccessful in determining location to being successful. + */ +#define FLP_STATUS_LOCATION_AVAILABLE 0 +/** + * Status to return in flp_status_callback when your implementation transitions + * from being successful in determining location to being unsuccessful. + */ +#define FLP_STATUS_LOCATION_UNAVAILABLE 1 + +/** + * This constant is used with the batched locations + * APIs. Batching is mandatory when FLP implementation + * is supported. If the flag is set, the hardware implementation + * will wake up the application processor when the FIFO is full, + * If the flag is not set, the hardware implementation will drop + * the oldest data when the FIFO is full. + */ +#define FLP_BATCH_WAKEUP_ON_FIFO_FULL 0x0000001 + +/** + * While batching, the implementation should not call the + * flp_location_callback on every location fix. However, + * sometimes in high power mode, the system might need + * a location callback every single time the location + * fix has been obtained. This flag controls that option. + * Its the responsibility of the upper layers (caller) to switch + * it off, if it knows that the AP might go to sleep. + * When this bit is on amidst a batching session, batching should + * continue while location fixes are reported in real time. + */ +#define FLP_BATCH_CALLBACK_ON_LOCATION_FIX 0x0000002 + +/** Flags to indicate which values are valid in a FlpLocation. */ +typedef uint16_t FlpLocationFlags; + +// IMPORTANT: Note that the following values must match +// constants in the corresponding java file. + +/** FlpLocation has valid latitude and longitude. */ +#define FLP_LOCATION_HAS_LAT_LONG (1U<<0) +/** FlpLocation has valid altitude. */ +#define FLP_LOCATION_HAS_ALTITUDE (1U<<1) +/** FlpLocation has valid speed. */ +#define FLP_LOCATION_HAS_SPEED (1U<<2) +/** FlpLocation has valid bearing. */ +#define FLP_LOCATION_HAS_BEARING (1U<<4) +/** FlpLocation has valid accuracy. */ +#define FLP_LOCATION_HAS_ACCURACY (1U<<8) + + +typedef int64_t FlpUtcTime; + +/** Represents a location. */ +typedef struct { + /** set to sizeof(FlpLocation) */ + size_t size; + + /** Flags associated with the location object. */ + FlpLocationFlags flags; + + /** Represents latitude in degrees. */ + double latitude; + + /** Represents longitude in degrees. */ + double longitude; + + /** + * Represents altitude in meters above the WGS 84 reference + * ellipsoid. */ + double altitude; + + /** Represents speed in meters per second. */ + float speed; + + /** Represents heading in degrees. */ + float bearing; + + /** Represents expected accuracy in meters. */ + float accuracy; + + /** Timestamp for the location fix. */ + FlpUtcTime timestamp; + + /** Sources used, will be Bitwise OR of the FLP_TECH_MASK bits. */ + uint32_t sources_used; +} FlpLocation; + +typedef enum { + ASSOCIATE_JVM, + DISASSOCIATE_JVM, +} ThreadEvent; + +/** + * Callback with location information. + * Can only be called from a thread associated to JVM using set_thread_event_cb. + * Parameters: + * num_locations is the number of batched locations available. + * location is the pointer to an array of pointers to location objects. + */ +typedef void (*flp_location_callback)(int32_t num_locations, FlpLocation** location); + +/** + * Callback utility for acquiring a wakelock. + * This can be used to prevent the CPU from suspending while handling FLP events. + */ +typedef void (*flp_acquire_wakelock)(); + +/** + * Callback utility for releasing the FLP wakelock. + */ +typedef void (*flp_release_wakelock)(); + +/** + * Callback for associating a thread that can call into the Java framework code. + * This must be used to initialize any threads that report events up to the framework. + * Return value: + * FLP_RESULT_SUCCESS on success. + * FLP_RESULT_ERROR if the association failed in the current thread. + */ +typedef int (*flp_set_thread_event)(ThreadEvent event); + +/** + * Callback for technologies supported by this implementation. + * + * Parameters: capabilities is a bitmask of FLP_CAPABILITY_* values describing + * which features your implementation supports. You should support + * CAPABILITY_GNSS at a minimum for your implementation to be utilized. You can + * return 0 in FlpGeofenceCallbacks to indicate you don't support geofencing, + * or 0 in FlpCallbacks to indicate you don't support location batching. + */ +typedef void (*flp_capabilities_callback)(int capabilities); + +/** + * Callback with status information on the ability to compute location. + * To avoid waking up the application processor you should only send + * changes in status (you shouldn't call this method twice in a row + * with the same status value). As a guideline you should not call this + * more frequently then the requested batch period set with period_ns + * in FlpBatchOptions. For example if period_ns is set to 5 minutes and + * the status changes many times in that interval, you should only report + * one status change every 5 minutes. + * + * Parameters: + * status is one of FLP_STATUS_LOCATION_AVAILABLE + * or FLP_STATUS_LOCATION_UNAVAILABLE. + */ +typedef void (*flp_status_callback)(int32_t status); + +/** FLP callback structure. */ +typedef struct { + /** set to sizeof(FlpCallbacks) */ + size_t size; + flp_location_callback location_cb; + flp_acquire_wakelock acquire_wakelock_cb; + flp_release_wakelock release_wakelock_cb; + flp_set_thread_event set_thread_event_cb; + flp_capabilities_callback flp_capabilities_cb; + flp_status_callback flp_status_cb; +} FlpCallbacks; + + +/** Options with the batching FLP APIs */ +typedef struct { + /** + * Maximum power in mW that the underlying implementation + * can use for this batching call. + * If max_power_allocation_mW is 0, only fixes that are generated + * at no additional cost of power shall be reported. + */ + double max_power_allocation_mW; + + /** Bitwise OR of the FLP_TECH_MASKS to use */ + uint32_t sources_to_use; + + /** + * FLP_BATCH_WAKEUP_ON_FIFO_FULL - If set the hardware + * will wake up the AP when the buffer is full. If not set, the + * hardware will drop the oldest location object. + * + * FLP_BATCH_CALLBACK_ON_LOCATION_FIX - If set the location + * callback will be called every time there is a location fix. + * Its the responsibility of the upper layers (caller) to switch + * it off, if it knows that the AP might go to sleep. When this + * bit is on amidst a batching session, batching should continue + * while location fixes are reported in real time. + * + * Other flags to be bitwised ORed in the future. + */ + uint32_t flags; + + /** + * Frequency with which location needs to be batched in nano + * seconds. + */ + int64_t period_ns; + + /** + * The smallest displacement between reported locations in meters. + * + * If set to 0, then you should report locations at the requested + * interval even if the device is stationary. If positive, you + * can use this parameter as a hint to save power (e.g. throttling + * location period if the user hasn't traveled close to the displacement + * threshold). Even small positive values can be interpreted to mean + * that you don't have to compute location when the device is stationary. + * + * There is no need to filter location delivery based on this parameter. + * Locations can be delivered even if they have a displacement smaller than + * requested. This parameter can safely be ignored at the cost of potential + * power savings. + */ + float smallest_displacement_meters; +} FlpBatchOptions; + +#define FLP_RESULT_SUCCESS 0 +#define FLP_RESULT_ERROR -1 +#define FLP_RESULT_INSUFFICIENT_MEMORY -2 +#define FLP_RESULT_TOO_MANY_GEOFENCES -3 +#define FLP_RESULT_ID_EXISTS -4 +#define FLP_RESULT_ID_UNKNOWN -5 +#define FLP_RESULT_INVALID_GEOFENCE_TRANSITION -6 + +/** + * Represents the standard FLP interface. + */ +typedef struct { + /** + * set to sizeof(FlpLocationInterface) + */ + size_t size; + + /** + * Opens the interface and provides the callback routines + * to the implementation of this interface. Once called you should respond + * by calling the flp_capabilities_callback in FlpCallbacks to + * specify the capabilities that your implementation supports. + */ + int (*init)(FlpCallbacks* callbacks ); + + /** + * Return the batch size (in number of FlpLocation objects) + * available in the hardware. Note, different HW implementations + * may have different sample sizes. This shall return number + * of samples defined in the format of FlpLocation. + * This will be used by the upper layer, to decide on the batching + * interval and whether the AP should be woken up or not. + */ + int (*get_batch_size)(); + + /** + * Start batching locations. This API is primarily used when the AP is + * asleep and the device can batch locations in the hardware. + * flp_location_callback is used to return the locations. When the buffer + * is full and FLP_BATCH_WAKEUP_ON_FIFO_FULL is used, the AP is woken up. + * When the buffer is full and FLP_BATCH_WAKEUP_ON_FIFO_FULL is not set, + * the oldest location object is dropped. In this case the AP will not be + * woken up. The upper layer will use get_batched_location + * API to explicitly ask for the location. + * If FLP_BATCH_CALLBACK_ON_LOCATION_FIX is set, the implementation + * will call the flp_location_callback every single time there is a location + * fix. This overrides FLP_BATCH_WAKEUP_ON_FIFO_FULL flag setting. + * It's the responsibility of the upper layers (caller) to switch + * it off, if it knows that the AP might go to sleep. This is useful + * for nagivational applications when the system is in high power mode. + * Parameters: + * id - Id for the request. + * options - See FlpBatchOptions struct definition. + * Return value: + * FLP_RESULT_SUCCESS on success, FLP_RESULT_INSUFFICIENT_MEMORY, + * FLP_RESULT_ID_EXISTS, FLP_RESULT_ERROR on failure. + */ + int (*start_batching)(int id, FlpBatchOptions* options); + + /** + * Update FlpBatchOptions associated with a batching request. + * When a batching operation is in progress and a batching option + * such as FLP_BATCH_WAKEUP_ON_FIFO_FULL needs to be updated, this API + * will be used. For instance, this can happen when the AP is awake and + * the maps application is being used. + * Parameters: + * id - Id of an existing batch request. + * new_options - Updated FlpBatchOptions + * Return value: + * FLP_RESULT_SUCCESS on success, FLP_RESULT_ID_UNKNOWN, + * FLP_RESULT_ERROR on error. + */ + int (*update_batching_options)(int id, FlpBatchOptions* new_options); + + /** + * Stop batching. + * Parameters: + * id - Id for the request. + * Return Value: + * FLP_RESULT_SUCCESS on success, FLP_RESULT_ID_UNKNOWN or + * FLP_RESULT_ERROR on failure. + */ + int (*stop_batching)(int id); + + /** + * Closes the interface. If any batch operations are in progress, + * they should be stopped. + */ + void (*cleanup)(); + + /** + * Get the fused location that was batched. + * flp_location_callback is used to return the location. The location object + * is dropped from the buffer only when the buffer is full. Do not remove it + * from the buffer just because it has been returned using the callback. + * In other words, when there is no new location object, two calls to + * get_batched_location(1) should return the same location object. + * Parameters: + * last_n_locations - Number of locations to get. This can be one or many. + * If the last_n_locations is 1, you get the latest location known to the + * hardware. + */ + void (*get_batched_location)(int last_n_locations); + + /** + * Injects current location from another location provider + * latitude and longitude are measured in degrees + * expected accuracy is measured in meters + * Parameters: + * location - The location object being injected. + * Return value: FLP_RESULT_SUCCESS or FLP_RESULT_ERROR. + */ + int (*inject_location)(FlpLocation* location); + + /** + * Get a pointer to extension information. + */ + const void* (*get_extension)(const char* name); + + /** + * Retrieve all batched locations currently stored and clear the buffer. + * flp_location_callback MUST be called in response, even if there are + * no locations to flush (in which case num_locations should be 0). + * Subsequent calls to get_batched_location or flush_batched_locations + * should not return any of the locations returned in this call. + */ + void (*flush_batched_locations)(); +} FlpLocationInterface; + +struct flp_device_t { + struct hw_device_t common; + + /** + * Get a handle to the FLP Interface. + */ + const FlpLocationInterface* (*get_flp_interface)(struct flp_device_t* dev); +}; + +/** + * Callback for reports diagnostic data into the Java framework code. +*/ +typedef void (*report_data)(char* data, int length); + +/** + * FLP diagnostic callback structure. + * Currently, not used - but this for future extension. + */ +typedef struct { + /** set to sizeof(FlpDiagnosticCallbacks) */ + size_t size; + + flp_set_thread_event set_thread_event_cb; + + /** reports diagnostic data into the Java framework code */ + report_data data_cb; +} FlpDiagnosticCallbacks; + +/** Extended interface for diagnostic support. */ +typedef struct { + /** set to sizeof(FlpDiagnosticInterface) */ + size_t size; + + /** + * Opens the diagnostic interface and provides the callback routines + * to the implemenation of this interface. + */ + void (*init)(FlpDiagnosticCallbacks* callbacks); + + /** + * Injects diagnostic data into the FLP subsystem. + * Return 0 on success, -1 on error. + **/ + int (*inject_data)(char* data, int length ); +} FlpDiagnosticInterface; + +/** + * Context setting information. + * All these settings shall be injected to FLP HAL at FLP init time. + * Following that, only the changed setting need to be re-injected + * upon changes. + */ + +#define FLP_DEVICE_CONTEXT_GPS_ENABLED (1U<<0) +#define FLP_DEVICE_CONTEXT_AGPS_ENABLED (1U<<1) +#define FLP_DEVICE_CONTEXT_NETWORK_POSITIONING_ENABLED (1U<<2) +#define FLP_DEVICE_CONTEXT_WIFI_CONNECTIVITY_ENABLED (1U<<3) +#define FLP_DEVICE_CONTEXT_WIFI_POSITIONING_ENABLED (1U<<4) +#define FLP_DEVICE_CONTEXT_HW_NETWORK_POSITIONING_ENABLED (1U<<5) +#define FLP_DEVICE_CONTEXT_AIRPLANE_MODE_ON (1U<<6) +#define FLP_DEVICE_CONTEXT_DATA_ENABLED (1U<<7) +#define FLP_DEVICE_CONTEXT_ROAMING_ENABLED (1U<<8) +#define FLP_DEVICE_CONTEXT_CURRENTLY_ROAMING (1U<<9) +#define FLP_DEVICE_CONTEXT_SENSOR_ENABLED (1U<<10) +#define FLP_DEVICE_CONTEXT_BLUETOOTH_ENABLED (1U<<11) +#define FLP_DEVICE_CONTEXT_CHARGER_ON (1U<<12) + +/** Extended interface for device context support. */ +typedef struct { + /** set to sizeof(FlpDeviceContextInterface) */ + size_t size; + + /** + * Injects debug data into the FLP subsystem. + * Return 0 on success, -1 on error. + **/ + int (*inject_device_context)(uint32_t enabledMask); +} FlpDeviceContextInterface; + + +/** + * There are 3 states associated with a Geofence: Inside, Outside, Unknown. + * There are 3 transitions: ENTERED, EXITED, UNCERTAIN. + * + * An example state diagram with confidence level: 95% and Unknown time limit + * set as 30 secs is shown below. (confidence level and Unknown time limit are + * explained latter) + * ____________________________ + * | Unknown (30 secs) | + * """""""""""""""""""""""""""" + * ^ | | ^ + * UNCERTAIN| |ENTERED EXITED| |UNCERTAIN + * | v v | + * ________ EXITED _________ + * | Inside | -----------> | Outside | + * | | <----------- | | + * """""""" ENTERED """"""""" + * + * Inside state: We are 95% confident that the user is inside the geofence. + * Outside state: We are 95% confident that the user is outside the geofence + * Unknown state: Rest of the time. + * + * The Unknown state is better explained with an example: + * + * __________ + * | c| + * | ___ | _______ + * | |a| | | b | + * | """ | """"""" + * | | + * """""""""" + * In the diagram above, "a" and "b" are 2 geofences and "c" is the accuracy + * circle reported by the FLP subsystem. Now with regard to "b", the system is + * confident that the user is outside. But with regard to "a" is not confident + * whether it is inside or outside the geofence. If the accuracy remains the + * same for a sufficient period of time, the UNCERTAIN transition would be + * triggered with the state set to Unknown. If the accuracy improves later, an + * appropriate transition should be triggered. This "sufficient period of time" + * is defined by the parameter in the add_geofence_area API. + * In other words, Unknown state can be interpreted as a state in which the + * FLP subsystem isn't confident enough that the user is either inside or + * outside the Geofence. It moves to Unknown state only after the expiry of the + * timeout. + * + * The geofence callback needs to be triggered for the ENTERED and EXITED + * transitions, when the FLP system is confident that the user has entered + * (Inside state) or exited (Outside state) the Geofence. An implementation + * which uses a value of 95% as the confidence is recommended. The callback + * should be triggered only for the transitions requested by the + * add_geofence_area call. + * + * Even though the diagram and explanation talks about states and transitions, + * the callee is only interested in the transistions. The states are mentioned + * here for illustrative purposes. + * + * Startup Scenario: When the device boots up, if an application adds geofences, + * and then we get an accurate FLP location fix, it needs to trigger the + * appropriate (ENTERED or EXITED) transition for every Geofence it knows about. + * By default, all the Geofences will be in the Unknown state. + * + * When the FLP system is unavailable, flp_geofence_status_callback should be + * called to inform the upper layers of the same. Similarly, when it becomes + * available the callback should be called. This is a global state while the + * UNKNOWN transition described above is per geofence. + * + */ +#define FLP_GEOFENCE_TRANSITION_ENTERED (1L<<0) +#define FLP_GEOFENCE_TRANSITION_EXITED (1L<<1) +#define FLP_GEOFENCE_TRANSITION_UNCERTAIN (1L<<2) + +#define FLP_GEOFENCE_MONITOR_STATUS_UNAVAILABLE (1L<<0) +#define FLP_GEOFENCE_MONITOR_STATUS_AVAILABLE (1L<<1) + +/** + * The callback associated with the geofence. + * Parameters: + * geofence_id - The id associated with the add_geofence_area. + * location - The current location as determined by the FLP subsystem. + * transition - Can be one of FLP_GEOFENCE_TRANSITION_ENTERED, FLP_GEOFENCE_TRANSITION_EXITED, + * FLP_GEOFENCE_TRANSITION_UNCERTAIN. + * timestamp - Timestamp when the transition was detected; -1 if not available. + * sources_used - Bitwise OR of FLP_TECH_MASK flags indicating which + * subsystems were used. + * + * The callback should only be called when the caller is interested in that + * particular transition. For instance, if the caller is interested only in + * ENTERED transition, then the callback should NOT be called with the EXITED + * transition. + * + * IMPORTANT: If a transition is triggered resulting in this callback, the + * subsystem will wake up the application processor, if its in suspend state. + */ +typedef void (*flp_geofence_transition_callback) (int32_t geofence_id, FlpLocation* location, + int32_t transition, FlpUtcTime timestamp, uint32_t sources_used); + +/** + * The callback associated with the availablity of one the sources used for geofence + * monitoring by the FLP sub-system For example, if the GPS system determines that it cannot + * monitor geofences because of lack of reliability or unavailability of the GPS signals, + * it will call this callback with FLP_GEOFENCE_MONITOR_STATUS_UNAVAILABLE parameter and the + * source set to FLP_TECH_MASK_GNSS. + * + * Parameters: + * status - FLP_GEOFENCE_MONITOR_STATUS_UNAVAILABLE or FLP_GEOFENCE_MONITOR_STATUS_AVAILABLE. + * source - One of the FLP_TECH_MASKS + * last_location - Last known location. + */ +typedef void (*flp_geofence_monitor_status_callback) (int32_t status, uint32_t source, + FlpLocation* last_location); + +/** + * The callback associated with the add_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * result - FLP_RESULT_SUCCESS + * FLP_RESULT_ERROR_TOO_MANY_GEOFENCES - geofence limit has been reached. + * FLP_RESULT_ID_EXISTS - geofence with id already exists + * FLP_RESULT_INVALID_GEOFENCE_TRANSITION - the monitorTransition contains an + * invalid transition + * FLP_RESULT_ERROR - for other errors. + */ +typedef void (*flp_geofence_add_callback) (int32_t geofence_id, int32_t result); + +/** + * The callback associated with the remove_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * result - FLP_RESULT_SUCCESS + * FLP_RESULT_ID_UNKNOWN - for invalid id + * FLP_RESULT_ERROR for others. + */ +typedef void (*flp_geofence_remove_callback) (int32_t geofence_id, int32_t result); + + +/** + * The callback associated with the pause_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * result - FLP_RESULT_SUCCESS + * FLP_RESULT__ID_UNKNOWN - for invalid id + * FLP_RESULT_INVALID_TRANSITION - + * when monitor_transitions is invalid + * FLP_RESULT_ERROR for others. + */ +typedef void (*flp_geofence_pause_callback) (int32_t geofence_id, int32_t result); + +/** + * The callback associated with the resume_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * result - FLP_RESULT_SUCCESS + * FLP_RESULT_ID_UNKNOWN - for invalid id + * FLP_RESULT_ERROR for others. + */ +typedef void (*flp_geofence_resume_callback) (int32_t geofence_id, int32_t result); + +typedef struct { + /** set to sizeof(FlpGeofenceCallbacks) */ + size_t size; + flp_geofence_transition_callback geofence_transition_callback; + flp_geofence_monitor_status_callback geofence_status_callback; + flp_geofence_add_callback geofence_add_callback; + flp_geofence_remove_callback geofence_remove_callback; + flp_geofence_pause_callback geofence_pause_callback; + flp_geofence_resume_callback geofence_resume_callback; + flp_set_thread_event set_thread_event_cb; + flp_capabilities_callback flp_capabilities_cb; +} FlpGeofenceCallbacks; + + +/** Type of geofence */ +typedef enum { + TYPE_CIRCLE = 0, +} GeofenceType; + +/** Circular geofence is represented by lat / long / radius */ +typedef struct { + double latitude; + double longitude; + double radius_m; +} GeofenceCircle; + +/** Represents the type of geofence and data */ +typedef struct { + GeofenceType type; + union { + GeofenceCircle circle; + } geofence; +} GeofenceData; + +/** Geofence Options */ +typedef struct { + /** + * The current state of the geofence. For example, if + * the system already knows that the user is inside the geofence, + * this will be set to FLP_GEOFENCE_TRANSITION_ENTERED. In most cases, it + * will be FLP_GEOFENCE_TRANSITION_UNCERTAIN. */ + int last_transition; + + /** + * Transitions to monitor. Bitwise OR of + * FLP_GEOFENCE_TRANSITION_ENTERED, FLP_GEOFENCE_TRANSITION_EXITED and + * FLP_GEOFENCE_TRANSITION_UNCERTAIN. + */ + int monitor_transitions; + + /** + * Defines the best-effort description + * of how soon should the callback be called when the transition + * associated with the Geofence is triggered. For instance, if set + * to 1000 millseconds with FLP_GEOFENCE_TRANSITION_ENTERED, the callback + * should be called 1000 milliseconds within entering the geofence. + * This parameter is defined in milliseconds. + * NOTE: This is not to be confused with the rate that the GPS is + * polled at. It is acceptable to dynamically vary the rate of + * sampling the GPS for power-saving reasons; thus the rate of + * sampling may be faster or slower than this. + */ + int notification_responsivenes_ms; + + /** + * The time limit after which the UNCERTAIN transition + * should be triggered. This paramter is defined in milliseconds. + */ + int unknown_timer_ms; + + /** + * The sources to use for monitoring geofences. Its a BITWISE-OR + * of FLP_TECH_MASK flags. + */ + uint32_t sources_to_use; +} GeofenceOptions; + +/** Geofence struct */ +typedef struct { + int32_t geofence_id; + GeofenceData* data; + GeofenceOptions* options; +} Geofence; + +/** Extended interface for FLP_Geofencing support */ +typedef struct { + /** set to sizeof(FlpGeofencingInterface) */ + size_t size; + + /** + * Opens the geofence interface and provides the callback routines + * to the implemenation of this interface. Once called you should respond + * by calling the flp_capabilities_callback in FlpGeofenceCallbacks to + * specify the capabilities that your implementation supports. + */ + void (*init)( FlpGeofenceCallbacks* callbacks ); + + /** + * Add a list of geofences. + * Parameters: + * number_of_geofences - The number of geofences that needed to be added. + * geofences - Pointer to array of pointers to Geofence structure. + */ + void (*add_geofences) (int32_t number_of_geofences, Geofence** geofences); + + /** + * Pause monitoring a particular geofence. + * Parameters: + * geofence_id - The id for the geofence. + */ + void (*pause_geofence) (int32_t geofence_id); + + /** + * Resume monitoring a particular geofence. + * Parameters: + * geofence_id - The id for the geofence. + * monitor_transitions - Which transitions to monitor. Bitwise OR of + * FLP_GEOFENCE_TRANSITION_ENTERED, FLP_GEOFENCE_TRANSITION_EXITED and + * FLP_GEOFENCE_TRANSITION_UNCERTAIN. + * This supersedes the value associated provided in the + * add_geofence_area call. + */ + void (*resume_geofence) (int32_t geofence_id, int monitor_transitions); + + /** + * Modify a particular geofence option. + * Parameters: + * geofence_id - The id for the geofence. + * options - Various options associated with the geofence. See + * GeofenceOptions structure for details. + */ + void (*modify_geofence_option) (int32_t geofence_id, GeofenceOptions* options); + + /** + * Remove a list of geofences. After the function returns, no notifications + * should be sent. + * Parameter: + * number_of_geofences - The number of geofences that needed to be added. + * geofence_id - Pointer to array of geofence_ids to be removed. + */ + void (*remove_geofences) (int32_t number_of_geofences, int32_t* geofence_id); +} FlpGeofencingInterface; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_FLP_H */ + diff --git a/third_party/android_hardware_libhardware/include/hardware/gatekeeper.h b/third_party/android_hardware_libhardware/include/hardware/gatekeeper.h new file mode 100644 index 00000000000000..2bb2b08c39c1b1 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/gatekeeper.h @@ -0,0 +1,190 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_HARDWARE_GATEKEEPER_H +#define ANDROID_HARDWARE_GATEKEEPER_H + +#include +#include +#include + +__BEGIN_DECLS + +#define GATEKEEPER_HARDWARE_MODULE_ID "gatekeeper" + +#define GATEKEEPER_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) + +#define HARDWARE_GATEKEEPER "gatekeeper" + +struct gatekeeper_module { + /** + * Comon methods of the gatekeeper module. This *must* be the first member of + * gatekeeper_module as users of this structure will cast a hw_module_t to + * a gatekeeper_module pointer in the appropriate context. + */ + hw_module_t common; +}; + +struct gatekeeper_device { + /** + * Common methods of the gatekeeper device. As above, this must be the first + * member of keymaster_device. + */ + hw_device_t common; + + /** + * Enrolls desired_password, which should be derived from a user selected pin or password, + * with the authentication factor private key used only for enrolling authentication + * factor data. + * + * If there was already a password enrolled, it should be provided in + * current_password_handle, along with the current password in current_password + * that should validate against current_password_handle. + * + * Parameters: + * - dev: pointer to gatekeeper_device acquired via calls to gatekeeper_open + * - uid: the Android user identifier + * + * - current_password_handle: the currently enrolled password handle the user + * wants to replace. May be null if there's no currently enrolled password. + * - current_password_handle_length: the length in bytes of the buffer pointed + * at by current_password_handle. Must be 0 if current_password_handle is NULL. + * + * - current_password: the user's current password in plain text. If presented, + * it MUST verify against current_password_handle. + * - current_password_length: the size in bytes of the buffer pointed at by + * current_password. Must be 0 if the current_password is NULL. + * + * - desired_password: the new password the user wishes to enroll in plain-text. + * Cannot be NULL. + * - desired_password_length: the length in bytes of the buffer pointed at by + * desired_password. + * + * - enrolled_password_handle: on success, a buffer will be allocated with the + * new password handle referencing the password provided in desired_password. + * This buffer can be used on subsequent calls to enroll or verify. + * The caller is responsible for deallocating this buffer via a call to delete[] + * - enrolled_password_handle_length: pointer to the length in bytes of the buffer allocated + * by this function and pointed to by *enrolled_password_handle_length. + * + * Returns: + * - 0 on success + * - An error code < 0 on failure, or + * - A timeout value T > 0 if the call should not be re-attempted until T milliseconds + * have elapsed. + * + * On error, enrolled_password_handle will not be allocated. + */ + int (*enroll)(const struct gatekeeper_device *dev, uint32_t uid, + const uint8_t *current_password_handle, uint32_t current_password_handle_length, + const uint8_t *current_password, uint32_t current_password_length, + const uint8_t *desired_password, uint32_t desired_password_length, + uint8_t **enrolled_password_handle, uint32_t *enrolled_password_handle_length); + + /** + * Verifies provided_password matches enrolled_password_handle. + * + * Implementations of this module may retain the result of this call + * to attest to the recency of authentication. + * + * On success, writes the address of a verification token to auth_token, + * usable to attest password verification to other trusted services. Clients + * may pass NULL for this value. + * + * Parameters: + * - dev: pointer to gatekeeper_device acquired via calls to gatekeeper_open + * - uid: the Android user identifier + * + * - challenge: An optional challenge to authenticate against, or 0. Used when a separate + * authenticator requests password verification, or for transactional + * password authentication. + * + * - enrolled_password_handle: the currently enrolled password handle that the + * user wishes to verify against. + * - enrolled_password_handle_length: the length in bytes of the buffer pointed + * to by enrolled_password_handle + * + * - provided_password: the plaintext password to be verified against the + * enrolled_password_handle + * - provided_password_length: the length in bytes of the buffer pointed to by + * provided_password + * + * - auth_token: on success, a buffer containing the authentication token + * resulting from this verification is assigned to *auth_token. The caller + * is responsible for deallocating this memory via a call to delete[] + * - auth_token_length: on success, the length in bytes of the authentication + * token assigned to *auth_token will be assigned to *auth_token_length + * + * - request_reenroll: a request to the upper layers to re-enroll the verified + * password due to a version change. Not set if verification fails. + * + * Returns: + * - 0 on success + * - An error code < 0 on failure, or + * - A timeout value T > 0 if the call should not be re-attempted until T milliseconds + * have elapsed. + * On error, auth token will not be allocated + */ + int (*verify)(const struct gatekeeper_device *dev, uint32_t uid, uint64_t challenge, + const uint8_t *enrolled_password_handle, uint32_t enrolled_password_handle_length, + const uint8_t *provided_password, uint32_t provided_password_length, + uint8_t **auth_token, uint32_t *auth_token_length, bool *request_reenroll); + + /* + * Deletes the enrolled_password_handle associated wth the uid. Once deleted + * the user cannot be verified anymore. + * This function is optional and should be set to NULL if it is not implemented. + * + * Parameters + * - dev: pointer to gatekeeper_device acquired via calls to gatekeeper_open + * - uid: the Android user identifier + * + * Returns: + * - 0 on success + * - An error code < 0 on failure + */ + int (*delete_user)(const struct gatekeeper_device *dev, uint32_t uid); + + /* + * Deletes all the enrolled_password_handles for all uid's. Once called, + * no users will be enrolled on the device. + * This function is optional and should be set to NULL if it is not implemented. + * + * Parameters + * - dev: pointer to gatekeeper_device acquired via calls to gatekeeper_open + * + * Returns: + * - 0 on success + * - An error code < 0 on failure + */ + int (*delete_all_users)(const struct gatekeeper_device *dev); +}; + +typedef struct gatekeeper_device gatekeeper_device_t; + +static inline int gatekeeper_open(const struct hw_module_t *module, + gatekeeper_device_t **device) { + return module->methods->open(module, HARDWARE_GATEKEEPER, + (struct hw_device_t **) device); +} + +static inline int gatekeeper_close(gatekeeper_device_t *device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_HARDWARE_GATEKEEPER_H diff --git a/third_party/android_hardware_libhardware/include/hardware/gps.h b/third_party/android_hardware_libhardware/include/hardware/gps.h new file mode 100644 index 00000000000000..76b6cb7aed464b --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/gps.h @@ -0,0 +1,1871 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_GPS_H +#define ANDROID_INCLUDE_HARDWARE_GPS_H + +#include +#include +#include +#include +#include +#include + +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define GPS_HARDWARE_MODULE_ID "gps" + + +/** Milliseconds since January 1, 1970 */ +typedef int64_t GpsUtcTime; + +/** Maximum number of SVs for gps_sv_status_callback(). */ +#define GPS_MAX_SVS 32 + +/** Maximum number of Measurements in gps_measurement_callback(). */ +#define GPS_MAX_MEASUREMENT 32 + +/** Requested operational mode for GPS operation. */ +typedef uint32_t GpsPositionMode; +// IMPORTANT: Note that the following values must match +// constants in GpsLocationProvider.java. +/** Mode for running GPS standalone (no assistance). */ +#define GPS_POSITION_MODE_STANDALONE 0 +/** AGPS MS-Based mode. */ +#define GPS_POSITION_MODE_MS_BASED 1 +/** + * AGPS MS-Assisted mode. This mode is not maintained by the platform anymore. + * It is strongly recommended to use GPS_POSITION_MODE_MS_BASE instead. + */ +#define GPS_POSITION_MODE_MS_ASSISTED 2 + +/** Requested recurrence mode for GPS operation. */ +typedef uint32_t GpsPositionRecurrence; +// IMPORTANT: Note that the following values must match +// constants in GpsLocationProvider.java. +/** Receive GPS fixes on a recurring basis at a specified period. */ +#define GPS_POSITION_RECURRENCE_PERIODIC 0 +/** Request a single shot GPS fix. */ +#define GPS_POSITION_RECURRENCE_SINGLE 1 + +/** GPS status event values. */ +typedef uint16_t GpsStatusValue; +// IMPORTANT: Note that the following values must match +// constants in GpsLocationProvider.java. +/** GPS status unknown. */ +#define GPS_STATUS_NONE 0 +/** GPS has begun navigating. */ +#define GPS_STATUS_SESSION_BEGIN 1 +/** GPS has stopped navigating. */ +#define GPS_STATUS_SESSION_END 2 +/** GPS has powered on but is not navigating. */ +#define GPS_STATUS_ENGINE_ON 3 +/** GPS is powered off. */ +#define GPS_STATUS_ENGINE_OFF 4 + +/** Flags to indicate which values are valid in a GpsLocation. */ +typedef uint16_t GpsLocationFlags; +// IMPORTANT: Note that the following values must match +// constants in GpsLocationProvider.java. +/** GpsLocation has valid latitude and longitude. */ +#define GPS_LOCATION_HAS_LAT_LONG 0x0001 +/** GpsLocation has valid altitude. */ +#define GPS_LOCATION_HAS_ALTITUDE 0x0002 +/** GpsLocation has valid speed. */ +#define GPS_LOCATION_HAS_SPEED 0x0004 +/** GpsLocation has valid bearing. */ +#define GPS_LOCATION_HAS_BEARING 0x0008 +/** GpsLocation has valid accuracy. */ +#define GPS_LOCATION_HAS_ACCURACY 0x0010 + +/** Flags for the gps_set_capabilities callback. */ + +/** GPS HAL schedules fixes for GPS_POSITION_RECURRENCE_PERIODIC mode. + If this is not set, then the framework will use 1000ms for min_interval + and will start and call start() and stop() to schedule the GPS. + */ +#define GPS_CAPABILITY_SCHEDULING 0x0000001 +/** GPS supports MS-Based AGPS mode */ +#define GPS_CAPABILITY_MSB 0x0000002 +/** GPS supports MS-Assisted AGPS mode */ +#define GPS_CAPABILITY_MSA 0x0000004 +/** GPS supports single-shot fixes */ +#define GPS_CAPABILITY_SINGLE_SHOT 0x0000008 +/** GPS supports on demand time injection */ +#define GPS_CAPABILITY_ON_DEMAND_TIME 0x0000010 +/** GPS supports Geofencing */ +#define GPS_CAPABILITY_GEOFENCING 0x0000020 +/** GPS supports Measurements */ +#define GPS_CAPABILITY_MEASUREMENTS 0x0000040 +/** GPS supports Navigation Messages */ +#define GPS_CAPABILITY_NAV_MESSAGES 0x0000080 + +/** Flags used to specify which aiding data to delete + when calling delete_aiding_data(). */ +typedef uint16_t GpsAidingData; +// IMPORTANT: Note that the following values must match +// constants in GpsLocationProvider.java. +#define GPS_DELETE_EPHEMERIS 0x0001 +#define GPS_DELETE_ALMANAC 0x0002 +#define GPS_DELETE_POSITION 0x0004 +#define GPS_DELETE_TIME 0x0008 +#define GPS_DELETE_IONO 0x0010 +#define GPS_DELETE_UTC 0x0020 +#define GPS_DELETE_HEALTH 0x0040 +#define GPS_DELETE_SVDIR 0x0080 +#define GPS_DELETE_SVSTEER 0x0100 +#define GPS_DELETE_SADATA 0x0200 +#define GPS_DELETE_RTI 0x0400 +#define GPS_DELETE_CELLDB_INFO 0x8000 +#define GPS_DELETE_ALL 0xFFFF + +/** AGPS type */ +typedef uint16_t AGpsType; +#define AGPS_TYPE_SUPL 1 +#define AGPS_TYPE_C2K 2 + +typedef uint16_t AGpsSetIDType; +#define AGPS_SETID_TYPE_NONE 0 +#define AGPS_SETID_TYPE_IMSI 1 +#define AGPS_SETID_TYPE_MSISDN 2 + +typedef uint16_t ApnIpType; +#define APN_IP_INVALID 0 +#define APN_IP_IPV4 1 +#define APN_IP_IPV6 2 +#define APN_IP_IPV4V6 3 + +/** + * String length constants + */ +#define GPS_NI_SHORT_STRING_MAXLEN 256 +#define GPS_NI_LONG_STRING_MAXLEN 2048 + +/** + * GpsNiType constants + */ +typedef uint32_t GpsNiType; +#define GPS_NI_TYPE_VOICE 1 +#define GPS_NI_TYPE_UMTS_SUPL 2 +#define GPS_NI_TYPE_UMTS_CTRL_PLANE 3 + +/** + * GpsNiNotifyFlags constants + */ +typedef uint32_t GpsNiNotifyFlags; +/** NI requires notification */ +#define GPS_NI_NEED_NOTIFY 0x0001 +/** NI requires verification */ +#define GPS_NI_NEED_VERIFY 0x0002 +/** NI requires privacy override, no notification/minimal trace */ +#define GPS_NI_PRIVACY_OVERRIDE 0x0004 + +/** + * GPS NI responses, used to define the response in + * NI structures + */ +typedef int GpsUserResponseType; +#define GPS_NI_RESPONSE_ACCEPT 1 +#define GPS_NI_RESPONSE_DENY 2 +#define GPS_NI_RESPONSE_NORESP 3 + +/** + * NI data encoding scheme + */ +typedef int GpsNiEncodingType; +#define GPS_ENC_NONE 0 +#define GPS_ENC_SUPL_GSM_DEFAULT 1 +#define GPS_ENC_SUPL_UTF8 2 +#define GPS_ENC_SUPL_UCS2 3 +#define GPS_ENC_UNKNOWN -1 + +/** AGPS status event values. */ +typedef uint16_t AGpsStatusValue; +/** GPS requests data connection for AGPS. */ +#define GPS_REQUEST_AGPS_DATA_CONN 1 +/** GPS releases the AGPS data connection. */ +#define GPS_RELEASE_AGPS_DATA_CONN 2 +/** AGPS data connection initiated */ +#define GPS_AGPS_DATA_CONNECTED 3 +/** AGPS data connection completed */ +#define GPS_AGPS_DATA_CONN_DONE 4 +/** AGPS data connection failed */ +#define GPS_AGPS_DATA_CONN_FAILED 5 + +#define AGPS_REF_LOCATION_TYPE_GSM_CELLID 1 +#define AGPS_REF_LOCATION_TYPE_UMTS_CELLID 2 +#define AGPS_REG_LOCATION_TYPE_MAC 3 + +/** Network types for update_network_state "type" parameter */ +#define AGPS_RIL_NETWORK_TYPE_MOBILE 0 +#define AGPS_RIL_NETWORK_TYPE_WIFI 1 +#define AGPS_RIL_NETWORK_TYPE_MOBILE_MMS 2 +#define AGPS_RIL_NETWORK_TYPE_MOBILE_SUPL 3 +#define AGPS_RIL_NETWORK_TTYPE_MOBILE_DUN 4 +#define AGPS_RIL_NETWORK_TTYPE_MOBILE_HIPRI 5 +#define AGPS_RIL_NETWORK_TTYPE_WIMAX 6 + +/** + * Flags to indicate what fields in GpsClock are valid. + */ +typedef uint16_t GpsClockFlags; +/** A valid 'leap second' is stored in the data structure. */ +#define GPS_CLOCK_HAS_LEAP_SECOND (1<<0) +/** A valid 'time uncertainty' is stored in the data structure. */ +#define GPS_CLOCK_HAS_TIME_UNCERTAINTY (1<<1) +/** A valid 'full bias' is stored in the data structure. */ +#define GPS_CLOCK_HAS_FULL_BIAS (1<<2) +/** A valid 'bias' is stored in the data structure. */ +#define GPS_CLOCK_HAS_BIAS (1<<3) +/** A valid 'bias uncertainty' is stored in the data structure. */ +#define GPS_CLOCK_HAS_BIAS_UNCERTAINTY (1<<4) +/** A valid 'drift' is stored in the data structure. */ +#define GPS_CLOCK_HAS_DRIFT (1<<5) +/** A valid 'drift uncertainty' is stored in the data structure. */ +#define GPS_CLOCK_HAS_DRIFT_UNCERTAINTY (1<<6) + +/** + * Enumeration of the available values for the GPS Clock type. + */ +typedef uint8_t GpsClockType; +/** The type is not available ot it is unknown. */ +#define GPS_CLOCK_TYPE_UNKNOWN 0 +/** The source of the time value reported by GPS clock is the local hardware clock. */ +#define GPS_CLOCK_TYPE_LOCAL_HW_TIME 1 +/** + * The source of the time value reported by GPS clock is the GPS time derived from satellites + * (epoch = Jan 6, 1980) + */ +#define GPS_CLOCK_TYPE_GPS_TIME 2 + +/** + * Flags to indicate what fields in GpsMeasurement are valid. + */ +typedef uint32_t GpsMeasurementFlags; +/** A valid 'snr' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_SNR (1<<0) +/** A valid 'elevation' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_ELEVATION (1<<1) +/** A valid 'elevation uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_ELEVATION_UNCERTAINTY (1<<2) +/** A valid 'azimuth' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_AZIMUTH (1<<3) +/** A valid 'azimuth uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_AZIMUTH_UNCERTAINTY (1<<4) +/** A valid 'pseudorange' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_PSEUDORANGE (1<<5) +/** A valid 'pseudorange uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_PSEUDORANGE_UNCERTAINTY (1<<6) +/** A valid 'code phase' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CODE_PHASE (1<<7) +/** A valid 'code phase uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CODE_PHASE_UNCERTAINTY (1<<8) +/** A valid 'carrier frequency' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CARRIER_FREQUENCY (1<<9) +/** A valid 'carrier cycles' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CARRIER_CYCLES (1<<10) +/** A valid 'carrier phase' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CARRIER_PHASE (1<<11) +/** A valid 'carrier phase uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_CARRIER_PHASE_UNCERTAINTY (1<<12) +/** A valid 'bit number' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_BIT_NUMBER (1<<13) +/** A valid 'time from last bit' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_TIME_FROM_LAST_BIT (1<<14) +/** A valid 'doppler shift' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_DOPPLER_SHIFT (1<<15) +/** A valid 'doppler shift uncertainty' is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_DOPPLER_SHIFT_UNCERTAINTY (1<<16) +/** A valid 'used in fix' flag is stored in the data structure. */ +#define GPS_MEASUREMENT_HAS_USED_IN_FIX (1<<17) +/** The value of 'pseudorange rate' is uncorrected. */ +#define GPS_MEASUREMENT_HAS_UNCORRECTED_PSEUDORANGE_RATE (1<<18) + +/** + * Enumeration of the available values for the GPS Measurement's loss of lock. + */ +typedef uint8_t GpsLossOfLock; +/** The indicator is not available or it is unknown. */ +#define GPS_LOSS_OF_LOCK_UNKNOWN 0 +/** The measurement does not present any indication of loss of lock. */ +#define GPS_LOSS_OF_LOCK_OK 1 +/** Loss of lock between previous and current observation: cycle slip possible. */ +#define GPS_LOSS_OF_LOCK_CYCLE_SLIP 2 + +/** + * Enumeration of available values for the GPS Measurement's multipath indicator. + */ +typedef uint8_t GpsMultipathIndicator; +/** The indicator is not available or unknown. */ +#define GPS_MULTIPATH_INDICATOR_UNKNOWN 0 +/** The measurement has been indicated to use multipath. */ +#define GPS_MULTIPATH_INDICATOR_DETECTED 1 +/** The measurement has been indicated Not to use multipath. */ +#define GPS_MULTIPATH_INDICATOR_NOT_USED 2 + +/** + * Flags indicating the GPS measurement state. + * The expected behavior here is for GPS HAL to set all the flags that applies. For + * example, if the state for a satellite is only C/A code locked and bit synchronized, + * and there is still millisecond ambiguity, the state should be set as: + * GPS_MEASUREMENT_STATE_CODE_LOCK|GPS_MEASUREMENT_STATE_BIT_SYNC|GPS_MEASUREMENT_STATE_MSEC_AMBIGUOUS + * If GPS is still searching for a satellite, the corresponding state should be set to + * GPS_MEASUREMENT_STATE_UNKNOWN(0). + */ +typedef uint16_t GpsMeasurementState; +#define GPS_MEASUREMENT_STATE_UNKNOWN 0 +#define GPS_MEASUREMENT_STATE_CODE_LOCK (1<<0) +#define GPS_MEASUREMENT_STATE_BIT_SYNC (1<<1) +#define GPS_MEASUREMENT_STATE_SUBFRAME_SYNC (1<<2) +#define GPS_MEASUREMENT_STATE_TOW_DECODED (1<<3) +#define GPS_MEASUREMENT_STATE_MSEC_AMBIGUOUS (1<<4) + +/** + * Flags indicating the Accumulated Delta Range's states. + */ +typedef uint16_t GpsAccumulatedDeltaRangeState; +#define GPS_ADR_STATE_UNKNOWN 0 +#define GPS_ADR_STATE_VALID (1<<0) +#define GPS_ADR_STATE_RESET (1<<1) +#define GPS_ADR_STATE_CYCLE_SLIP (1<<2) + +/** + * Enumeration of available values to indicate the available GPS Navigation message types. + */ +typedef uint8_t GpsNavigationMessageType; +/** The message type is unknown. */ +#define GPS_NAVIGATION_MESSAGE_TYPE_UNKNOWN 0 +/** L1 C/A message contained in the structure. */ +#define GPS_NAVIGATION_MESSAGE_TYPE_L1CA 1 +/** L2-CNAV message contained in the structure. */ +#define GPS_NAVIGATION_MESSAGE_TYPE_L2CNAV 2 +/** L5-CNAV message contained in the structure. */ +#define GPS_NAVIGATION_MESSAGE_TYPE_L5CNAV 3 +/** CNAV-2 message contained in the structure. */ +#define GPS_NAVIGATION_MESSAGE_TYPE_CNAV2 4 + +/** + * Status of Navigation Message + * When a message is received properly without any parity error in its navigation words, the + * status should be set to NAV_MESSAGE_STATUS_PARITY_PASSED. But if a message is received + * with words that failed parity check, but GPS is able to correct those words, the status + * should be set to NAV_MESSAGE_STATUS_PARITY_REBUILT. + * No need to send any navigation message that contains words with parity error and cannot be + * corrected. + */ +typedef uint16_t NavigationMessageStatus; +#define NAV_MESSAGE_STATUS_UNKONW 0 +#define NAV_MESSAGE_STATUS_PARITY_PASSED (1<<0) +#define NAV_MESSAGE_STATUS_PARITY_REBUILT (1<<1) + +/** + * Name for the GPS XTRA interface. + */ +#define GPS_XTRA_INTERFACE "gps-xtra" + +/** + * Name for the GPS DEBUG interface. + */ +#define GPS_DEBUG_INTERFACE "gps-debug" + +/** + * Name for the AGPS interface. + */ +#define AGPS_INTERFACE "agps" + +/** + * Name of the Supl Certificate interface. + */ +#define SUPL_CERTIFICATE_INTERFACE "supl-certificate" + +/** + * Name for NI interface + */ +#define GPS_NI_INTERFACE "gps-ni" + +/** + * Name for the AGPS-RIL interface. + */ +#define AGPS_RIL_INTERFACE "agps_ril" + +/** + * Name for the GPS_Geofencing interface. + */ +#define GPS_GEOFENCING_INTERFACE "gps_geofencing" + +/** + * Name of the GPS Measurements interface. + */ +#define GPS_MEASUREMENT_INTERFACE "gps_measurement" + +/** + * Name of the GPS navigation message interface. + */ +#define GPS_NAVIGATION_MESSAGE_INTERFACE "gps_navigation_message" + +/** + * Name of the GNSS/GPS configuration interface. + */ +#define GNSS_CONFIGURATION_INTERFACE "gnss_configuration" + + +/** Represents a location. */ +typedef struct { + /** set to sizeof(GpsLocation) */ + size_t size; + /** Contains GpsLocationFlags bits. */ + uint16_t flags; + /** Represents latitude in degrees. */ + double latitude; + /** Represents longitude in degrees. */ + double longitude; + /** Represents altitude in meters above the WGS 84 reference + * ellipsoid. */ + double altitude; + /** Represents speed in meters per second. */ + float speed; + /** Represents heading in degrees. */ + float bearing; + /** Represents expected accuracy in meters. */ + float accuracy; + /** Timestamp for the location fix. */ + GpsUtcTime timestamp; +} GpsLocation; + +/** Represents the status. */ +typedef struct { + /** set to sizeof(GpsStatus) */ + size_t size; + GpsStatusValue status; +} GpsStatus; + +/** Represents SV information. */ +typedef struct { + /** set to sizeof(GpsSvInfo) */ + size_t size; + /** Pseudo-random number for the SV. */ + int prn; + /** Signal to noise ratio. */ + float snr; + /** Elevation of SV in degrees. */ + float elevation; + /** Azimuth of SV in degrees. */ + float azimuth; +} GpsSvInfo; + +/** Represents SV status. */ +typedef struct { + /** set to sizeof(GpsSvStatus) */ + size_t size; + + /** Number of SVs currently visible. */ + int num_svs; + + /** Contains an array of SV information. */ + GpsSvInfo sv_list[GPS_MAX_SVS]; + + /** Represents a bit mask indicating which SVs + * have ephemeris data. + */ + uint32_t ephemeris_mask; + + /** Represents a bit mask indicating which SVs + * have almanac data. + */ + uint32_t almanac_mask; + + /** + * Represents a bit mask indicating which SVs + * were used for computing the most recent position fix. + */ + uint32_t used_in_fix_mask; +} GpsSvStatus; + + +/* 2G and 3G */ +/* In 3G lac is discarded */ +typedef struct { + uint16_t type; + uint16_t mcc; + uint16_t mnc; + uint16_t lac; + uint32_t cid; +} AGpsRefLocationCellID; + +typedef struct { + uint8_t mac[6]; +} AGpsRefLocationMac; + +/** Represents ref locations */ +typedef struct { + uint16_t type; + union { + AGpsRefLocationCellID cellID; + AGpsRefLocationMac mac; + } u; +} AGpsRefLocation; + +/** Callback with location information. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* gps_location_callback)(GpsLocation* location); + +/** Callback with status information. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* gps_status_callback)(GpsStatus* status); + +/** + * Callback with SV status information. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* gps_sv_status_callback)(GpsSvStatus* sv_info); + +/** Callback for reporting NMEA sentences. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* gps_nmea_callback)(GpsUtcTime timestamp, const char* nmea, int length); + +/** Callback to inform framework of the GPS engine's capabilities. + * Capability parameter is a bit field of GPS_CAPABILITY_* flags. + */ +typedef void (* gps_set_capabilities)(uint32_t capabilities); + +/** Callback utility for acquiring the GPS wakelock. + * This can be used to prevent the CPU from suspending while handling GPS events. + */ +typedef void (* gps_acquire_wakelock)(); + +/** Callback utility for releasing the GPS wakelock. */ +typedef void (* gps_release_wakelock)(); + +/** Callback for requesting NTP time */ +typedef void (* gps_request_utc_time)(); + +/** Callback for creating a thread that can call into the Java framework code. + * This must be used to create any threads that report events up to the framework. + */ +typedef pthread_t (* gps_create_thread)(const char* name, void (*start)(void *), void* arg); + +/** GPS callback structure. */ +typedef struct { + /** set to sizeof(GpsCallbacks) */ + size_t size; + gps_location_callback location_cb; + gps_status_callback status_cb; + gps_sv_status_callback sv_status_cb; + gps_nmea_callback nmea_cb; + gps_set_capabilities set_capabilities_cb; + gps_acquire_wakelock acquire_wakelock_cb; + gps_release_wakelock release_wakelock_cb; + gps_create_thread create_thread_cb; + gps_request_utc_time request_utc_time_cb; +} GpsCallbacks; + + +/** Represents the standard GPS interface. */ +typedef struct { + /** set to sizeof(GpsInterface) */ + size_t size; + /** + * Opens the interface and provides the callback routines + * to the implementation of this interface. + */ + int (*init)( GpsCallbacks* callbacks ); + + /** Starts navigating. */ + int (*start)( void ); + + /** Stops navigating. */ + int (*stop)( void ); + + /** Closes the interface. */ + void (*cleanup)( void ); + + /** Injects the current time. */ + int (*inject_time)(GpsUtcTime time, int64_t timeReference, + int uncertainty); + + /** Injects current location from another location provider + * (typically cell ID). + * latitude and longitude are measured in degrees + * expected accuracy is measured in meters + */ + int (*inject_location)(double latitude, double longitude, float accuracy); + + /** + * Specifies that the next call to start will not use the + * information defined in the flags. GPS_DELETE_ALL is passed for + * a cold start. + */ + void (*delete_aiding_data)(GpsAidingData flags); + + /** + * min_interval represents the time between fixes in milliseconds. + * preferred_accuracy represents the requested fix accuracy in meters. + * preferred_time represents the requested time to first fix in milliseconds. + * + * 'mode' parameter should be one of GPS_POSITION_MODE_MS_BASE + * or GPS_POSITION_MODE_STANDALONE. + * It is allowed by the platform (and it is recommended) to fallback to + * GPS_POSITION_MODE_MS_BASE if GPS_POSITION_MODE_MS_ASSISTED is passed in, and + * GPS_POSITION_MODE_MS_BASED is supported. + */ + int (*set_position_mode)(GpsPositionMode mode, GpsPositionRecurrence recurrence, + uint32_t min_interval, uint32_t preferred_accuracy, uint32_t preferred_time); + + /** Get a pointer to extension information. */ + const void* (*get_extension)(const char* name); +} GpsInterface; + +/** Callback to request the client to download XTRA data. + * The client should download XTRA data and inject it by calling inject_xtra_data(). + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* gps_xtra_download_request)(); + +/** Callback structure for the XTRA interface. */ +typedef struct { + gps_xtra_download_request download_request_cb; + gps_create_thread create_thread_cb; +} GpsXtraCallbacks; + +/** Extended interface for XTRA support. */ +typedef struct { + /** set to sizeof(GpsXtraInterface) */ + size_t size; + /** + * Opens the XTRA interface and provides the callback routines + * to the implementation of this interface. + */ + int (*init)( GpsXtraCallbacks* callbacks ); + /** Injects XTRA data into the GPS. */ + int (*inject_xtra_data)( char* data, int length ); +} GpsXtraInterface; + +/** Extended interface for DEBUG support. */ +typedef struct { + /** set to sizeof(GpsDebugInterface) */ + size_t size; + + /** + * This function should return any information that the native + * implementation wishes to include in a bugreport. + */ + size_t (*get_internal_state)(char* buffer, size_t bufferSize); +} GpsDebugInterface; + +#pragma pack(push,4) +// We need to keep the alignment of this data structure to 4-bytes, to ensure that in 64-bit +// environments the size of this legacy definition does not collide with _v2. Implementations should +// be using _v2 and _v3, so it's OK to pay the 'unaligned' penalty in 64-bit if an old +// implementation is still in use. + +/** Represents the status of AGPS. */ +typedef struct { + /** set to sizeof(AGpsStatus_v1) */ + size_t size; + + AGpsType type; + AGpsStatusValue status; +} AGpsStatus_v1; + +#pragma pack(pop) + +/** Represents the status of AGPS augmented with a IPv4 address field. */ +typedef struct { + /** set to sizeof(AGpsStatus_v2) */ + size_t size; + + AGpsType type; + AGpsStatusValue status; + uint32_t ipaddr; +} AGpsStatus_v2; + +/* Represents the status of AGPS augmented to support IPv4 and IPv6. */ +typedef struct { + /** set to sizeof(AGpsStatus_v3) */ + size_t size; + + AGpsType type; + AGpsStatusValue status; + + /** + * Must be set to a valid IPv4 address if the field 'addr' contains an IPv4 + * address, or set to INADDR_NONE otherwise. + */ + uint32_t ipaddr; + + /** + * Must contain the IPv4 (AF_INET) or IPv6 (AF_INET6) address to report. + * Any other value of addr.ss_family will be rejected. + * */ + struct sockaddr_storage addr; +} AGpsStatus_v3; + +typedef AGpsStatus_v3 AGpsStatus; + +/** Callback with AGPS status information. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (* agps_status_callback)(AGpsStatus* status); + +/** Callback structure for the AGPS interface. */ +typedef struct { + agps_status_callback status_cb; + gps_create_thread create_thread_cb; +} AGpsCallbacks; + + +/** Extended interface for AGPS support. */ +typedef struct { + /** set to sizeof(AGpsInterface_v1) */ + size_t size; + + /** + * Opens the AGPS interface and provides the callback routines + * to the implementation of this interface. + */ + void (*init)( AGpsCallbacks* callbacks ); + /** + * Notifies that a data connection is available and sets + * the name of the APN to be used for SUPL. + */ + int (*data_conn_open)( const char* apn ); + /** + * Notifies that the AGPS data connection has been closed. + */ + int (*data_conn_closed)(); + /** + * Notifies that a data connection is not available for AGPS. + */ + int (*data_conn_failed)(); + /** + * Sets the hostname and port for the AGPS server. + */ + int (*set_server)( AGpsType type, const char* hostname, int port ); +} AGpsInterface_v1; + +/** + * Extended interface for AGPS support, it is augmented to enable to pass + * extra APN data. + */ +typedef struct { + /** set to sizeof(AGpsInterface_v2) */ + size_t size; + + /** + * Opens the AGPS interface and provides the callback routines to the + * implementation of this interface. + */ + void (*init)(AGpsCallbacks* callbacks); + /** + * Deprecated. + * If the HAL supports AGpsInterface_v2 this API will not be used, see + * data_conn_open_with_apn_ip_type for more information. + */ + int (*data_conn_open)(const char* apn); + /** + * Notifies that the AGPS data connection has been closed. + */ + int (*data_conn_closed)(); + /** + * Notifies that a data connection is not available for AGPS. + */ + int (*data_conn_failed)(); + /** + * Sets the hostname and port for the AGPS server. + */ + int (*set_server)(AGpsType type, const char* hostname, int port); + + /** + * Notifies that a data connection is available and sets the name of the + * APN, and its IP type, to be used for SUPL connections. + */ + int (*data_conn_open_with_apn_ip_type)( + const char* apn, + ApnIpType apnIpType); +} AGpsInterface_v2; + +typedef AGpsInterface_v2 AGpsInterface; + +/** Error codes associated with certificate operations */ +#define AGPS_CERTIFICATE_OPERATION_SUCCESS 0 +#define AGPS_CERTIFICATE_ERROR_GENERIC -100 +#define AGPS_CERTIFICATE_ERROR_TOO_MANY_CERTIFICATES -101 + +/** A data structure that represents an X.509 certificate using DER encoding */ +typedef struct { + size_t length; + u_char* data; +} DerEncodedCertificate; + +/** + * A type definition for SHA1 Fingerprints used to identify X.509 Certificates + * The Fingerprint is a digest of the DER Certificate that uniquely identifies it. + */ +typedef struct { + u_char data[20]; +} Sha1CertificateFingerprint; + +/** AGPS Interface to handle SUPL certificate operations */ +typedef struct { + /** set to sizeof(SuplCertificateInterface) */ + size_t size; + + /** + * Installs a set of Certificates used for SUPL connections to the AGPS server. + * If needed the HAL should find out internally any certificates that need to be removed to + * accommodate the certificates to install. + * The certificates installed represent a full set of valid certificates needed to connect to + * AGPS SUPL servers. + * The list of certificates is required, and all must be available at the same time, when trying + * to establish a connection with the AGPS Server. + * + * Parameters: + * certificates - A pointer to an array of DER encoded certificates that are need to be + * installed in the HAL. + * length - The number of certificates to install. + * Returns: + * AGPS_CERTIFICATE_OPERATION_SUCCESS if the operation is completed successfully + * AGPS_CERTIFICATE_ERROR_TOO_MANY_CERTIFICATES if the HAL cannot store the number of + * certificates attempted to be installed, the state of the certificates stored should + * remain the same as before on this error case. + * + * IMPORTANT: + * If needed the HAL should find out internally the set of certificates that need to be + * removed to accommodate the certificates to install. + */ + int (*install_certificates) ( const DerEncodedCertificate* certificates, size_t length ); + + /** + * Notifies the HAL that a list of certificates used for SUPL connections are revoked. It is + * expected that the given set of certificates is removed from the internal store of the HAL. + * + * Parameters: + * fingerprints - A pointer to an array of SHA1 Fingerprints to identify the set of + * certificates to revoke. + * length - The number of fingerprints provided. + * Returns: + * AGPS_CERTIFICATE_OPERATION_SUCCESS if the operation is completed successfully. + * + * IMPORTANT: + * If any of the certificates provided (through its fingerprint) is not known by the HAL, + * it should be ignored and continue revoking/deleting the rest of them. + */ + int (*revoke_certificates) ( const Sha1CertificateFingerprint* fingerprints, size_t length ); +} SuplCertificateInterface; + +/** Represents an NI request */ +typedef struct { + /** set to sizeof(GpsNiNotification) */ + size_t size; + + /** + * An ID generated by HAL to associate NI notifications and UI + * responses + */ + int notification_id; + + /** + * An NI type used to distinguish different categories of NI + * events, such as GPS_NI_TYPE_VOICE, GPS_NI_TYPE_UMTS_SUPL, ... + */ + GpsNiType ni_type; + + /** + * Notification/verification options, combinations of GpsNiNotifyFlags constants + */ + GpsNiNotifyFlags notify_flags; + + /** + * Timeout period to wait for user response. + * Set to 0 for no time out limit. + */ + int timeout; + + /** + * Default response when time out. + */ + GpsUserResponseType default_response; + + /** + * Requestor ID + */ + char requestor_id[GPS_NI_SHORT_STRING_MAXLEN]; + + /** + * Notification message. It can also be used to store client_id in some cases + */ + char text[GPS_NI_LONG_STRING_MAXLEN]; + + /** + * Client name decoding scheme + */ + GpsNiEncodingType requestor_id_encoding; + + /** + * Client name decoding scheme + */ + GpsNiEncodingType text_encoding; + + /** + * A pointer to extra data. Format: + * key_1 = value_1 + * key_2 = value_2 + */ + char extras[GPS_NI_LONG_STRING_MAXLEN]; + +} GpsNiNotification; + +/** Callback with NI notification. + * Can only be called from a thread created by create_thread_cb. + */ +typedef void (*gps_ni_notify_callback)(GpsNiNotification *notification); + +/** GPS NI callback structure. */ +typedef struct +{ + /** + * Sends the notification request from HAL to GPSLocationProvider. + */ + gps_ni_notify_callback notify_cb; + gps_create_thread create_thread_cb; +} GpsNiCallbacks; + +/** + * Extended interface for Network-initiated (NI) support. + */ +typedef struct +{ + /** set to sizeof(GpsNiInterface) */ + size_t size; + + /** Registers the callbacks for HAL to use. */ + void (*init) (GpsNiCallbacks *callbacks); + + /** Sends a response to HAL. */ + void (*respond) (int notif_id, GpsUserResponseType user_response); +} GpsNiInterface; + +struct gps_device_t { + struct hw_device_t common; + + /** + * Set the provided lights to the provided values. + * + * Returns: 0 on succes, error code on failure. + */ + const GpsInterface* (*get_gps_interface)(struct gps_device_t* dev); +}; + +#define AGPS_RIL_REQUEST_SETID_IMSI (1<<0L) +#define AGPS_RIL_REQUEST_SETID_MSISDN (1<<1L) + +#define AGPS_RIL_REQUEST_REFLOC_CELLID (1<<0L) +#define AGPS_RIL_REQUEST_REFLOC_MAC (1<<1L) + +typedef void (*agps_ril_request_set_id)(uint32_t flags); +typedef void (*agps_ril_request_ref_loc)(uint32_t flags); + +typedef struct { + agps_ril_request_set_id request_setid; + agps_ril_request_ref_loc request_refloc; + gps_create_thread create_thread_cb; +} AGpsRilCallbacks; + +/** Extended interface for AGPS_RIL support. */ +typedef struct { + /** set to sizeof(AGpsRilInterface) */ + size_t size; + /** + * Opens the AGPS interface and provides the callback routines + * to the implementation of this interface. + */ + void (*init)( AGpsRilCallbacks* callbacks ); + + /** + * Sets the reference location. + */ + void (*set_ref_location) (const AGpsRefLocation *agps_reflocation, size_t sz_struct); + /** + * Sets the set ID. + */ + void (*set_set_id) (AGpsSetIDType type, const char* setid); + + /** + * Send network initiated message. + */ + void (*ni_message) (uint8_t *msg, size_t len); + + /** + * Notify GPS of network status changes. + * These parameters match values in the android.net.NetworkInfo class. + */ + void (*update_network_state) (int connected, int type, int roaming, const char* extra_info); + + /** + * Notify GPS of network status changes. + * These parameters match values in the android.net.NetworkInfo class. + */ + void (*update_network_availability) (int avaiable, const char* apn); +} AGpsRilInterface; + +/** + * GPS Geofence. + * There are 3 states associated with a Geofence: Inside, Outside, Unknown. + * There are 3 transitions: ENTERED, EXITED, UNCERTAIN. + * + * An example state diagram with confidence level: 95% and Unknown time limit + * set as 30 secs is shown below. (confidence level and Unknown time limit are + * explained latter) + * ____________________________ + * | Unknown (30 secs) | + * """""""""""""""""""""""""""" + * ^ | | ^ + * UNCERTAIN| |ENTERED EXITED| |UNCERTAIN + * | v v | + * ________ EXITED _________ + * | Inside | -----------> | Outside | + * | | <----------- | | + * """""""" ENTERED """"""""" + * + * Inside state: We are 95% confident that the user is inside the geofence. + * Outside state: We are 95% confident that the user is outside the geofence + * Unknown state: Rest of the time. + * + * The Unknown state is better explained with an example: + * + * __________ + * | c| + * | ___ | _______ + * | |a| | | b | + * | """ | """"""" + * | | + * """""""""" + * In the diagram above, "a" and "b" are 2 geofences and "c" is the accuracy + * circle reported by the GPS subsystem. Now with regard to "b", the system is + * confident that the user is outside. But with regard to "a" is not confident + * whether it is inside or outside the geofence. If the accuracy remains the + * same for a sufficient period of time, the UNCERTAIN transition would be + * triggered with the state set to Unknown. If the accuracy improves later, an + * appropriate transition should be triggered. This "sufficient period of time" + * is defined by the parameter in the add_geofence_area API. + * In other words, Unknown state can be interpreted as a state in which the + * GPS subsystem isn't confident enough that the user is either inside or + * outside the Geofence. It moves to Unknown state only after the expiry of the + * timeout. + * + * The geofence callback needs to be triggered for the ENTERED and EXITED + * transitions, when the GPS system is confident that the user has entered + * (Inside state) or exited (Outside state) the Geofence. An implementation + * which uses a value of 95% as the confidence is recommended. The callback + * should be triggered only for the transitions requested by the + * add_geofence_area call. + * + * Even though the diagram and explanation talks about states and transitions, + * the callee is only interested in the transistions. The states are mentioned + * here for illustrative purposes. + * + * Startup Scenario: When the device boots up, if an application adds geofences, + * and then we get an accurate GPS location fix, it needs to trigger the + * appropriate (ENTERED or EXITED) transition for every Geofence it knows about. + * By default, all the Geofences will be in the Unknown state. + * + * When the GPS system is unavailable, gps_geofence_status_callback should be + * called to inform the upper layers of the same. Similarly, when it becomes + * available the callback should be called. This is a global state while the + * UNKNOWN transition described above is per geofence. + * + * An important aspect to note is that users of this API (framework), will use + * other subsystems like wifi, sensors, cell to handle Unknown case and + * hopefully provide a definitive state transition to the third party + * application. GPS Geofence will just be a signal indicating what the GPS + * subsystem knows about the Geofence. + * + */ +#define GPS_GEOFENCE_ENTERED (1<<0L) +#define GPS_GEOFENCE_EXITED (1<<1L) +#define GPS_GEOFENCE_UNCERTAIN (1<<2L) + +#define GPS_GEOFENCE_UNAVAILABLE (1<<0L) +#define GPS_GEOFENCE_AVAILABLE (1<<1L) + +#define GPS_GEOFENCE_OPERATION_SUCCESS 0 +#define GPS_GEOFENCE_ERROR_TOO_MANY_GEOFENCES -100 +#define GPS_GEOFENCE_ERROR_ID_EXISTS -101 +#define GPS_GEOFENCE_ERROR_ID_UNKNOWN -102 +#define GPS_GEOFENCE_ERROR_INVALID_TRANSITION -103 +#define GPS_GEOFENCE_ERROR_GENERIC -149 + +/** + * The callback associated with the geofence. + * Parameters: + * geofence_id - The id associated with the add_geofence_area. + * location - The current GPS location. + * transition - Can be one of GPS_GEOFENCE_ENTERED, GPS_GEOFENCE_EXITED, + * GPS_GEOFENCE_UNCERTAIN. + * timestamp - Timestamp when the transition was detected. + * + * The callback should only be called when the caller is interested in that + * particular transition. For instance, if the caller is interested only in + * ENTERED transition, then the callback should NOT be called with the EXITED + * transition. + * + * IMPORTANT: If a transition is triggered resulting in this callback, the GPS + * subsystem will wake up the application processor, if its in suspend state. + */ +typedef void (*gps_geofence_transition_callback) (int32_t geofence_id, GpsLocation* location, + int32_t transition, GpsUtcTime timestamp); + +/** + * The callback associated with the availability of the GPS system for geofencing + * monitoring. If the GPS system determines that it cannot monitor geofences + * because of lack of reliability or unavailability of the GPS signals, it will + * call this callback with GPS_GEOFENCE_UNAVAILABLE parameter. + * + * Parameters: + * status - GPS_GEOFENCE_UNAVAILABLE or GPS_GEOFENCE_AVAILABLE. + * last_location - Last known location. + */ +typedef void (*gps_geofence_status_callback) (int32_t status, GpsLocation* last_location); + +/** + * The callback associated with the add_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * status - GPS_GEOFENCE_OPERATION_SUCCESS + * GPS_GEOFENCE_ERROR_TOO_MANY_GEOFENCES - geofence limit has been reached. + * GPS_GEOFENCE_ERROR_ID_EXISTS - geofence with id already exists + * GPS_GEOFENCE_ERROR_INVALID_TRANSITION - the monitorTransition contains an + * invalid transition + * GPS_GEOFENCE_ERROR_GENERIC - for other errors. + */ +typedef void (*gps_geofence_add_callback) (int32_t geofence_id, int32_t status); + +/** + * The callback associated with the remove_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * status - GPS_GEOFENCE_OPERATION_SUCCESS + * GPS_GEOFENCE_ERROR_ID_UNKNOWN - for invalid id + * GPS_GEOFENCE_ERROR_GENERIC for others. + */ +typedef void (*gps_geofence_remove_callback) (int32_t geofence_id, int32_t status); + + +/** + * The callback associated with the pause_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * status - GPS_GEOFENCE_OPERATION_SUCCESS + * GPS_GEOFENCE_ERROR_ID_UNKNOWN - for invalid id + * GPS_GEOFENCE_ERROR_INVALID_TRANSITION - + * when monitor_transitions is invalid + * GPS_GEOFENCE_ERROR_GENERIC for others. + */ +typedef void (*gps_geofence_pause_callback) (int32_t geofence_id, int32_t status); + +/** + * The callback associated with the resume_geofence call. + * + * Parameter: + * geofence_id - Id of the geofence. + * status - GPS_GEOFENCE_OPERATION_SUCCESS + * GPS_GEOFENCE_ERROR_ID_UNKNOWN - for invalid id + * GPS_GEOFENCE_ERROR_GENERIC for others. + */ +typedef void (*gps_geofence_resume_callback) (int32_t geofence_id, int32_t status); + +typedef struct { + gps_geofence_transition_callback geofence_transition_callback; + gps_geofence_status_callback geofence_status_callback; + gps_geofence_add_callback geofence_add_callback; + gps_geofence_remove_callback geofence_remove_callback; + gps_geofence_pause_callback geofence_pause_callback; + gps_geofence_resume_callback geofence_resume_callback; + gps_create_thread create_thread_cb; +} GpsGeofenceCallbacks; + +/** Extended interface for GPS_Geofencing support */ +typedef struct { + /** set to sizeof(GpsGeofencingInterface) */ + size_t size; + + /** + * Opens the geofence interface and provides the callback routines + * to the implementation of this interface. + */ + void (*init)( GpsGeofenceCallbacks* callbacks ); + + /** + * Add a geofence area. This api currently supports circular geofences. + * Parameters: + * geofence_id - The id for the geofence. If a geofence with this id + * already exists, an error value (GPS_GEOFENCE_ERROR_ID_EXISTS) + * should be returned. + * latitude, longtitude, radius_meters - The lat, long and radius + * (in meters) for the geofence + * last_transition - The current state of the geofence. For example, if + * the system already knows that the user is inside the geofence, + * this will be set to GPS_GEOFENCE_ENTERED. In most cases, it + * will be GPS_GEOFENCE_UNCERTAIN. + * monitor_transition - Which transitions to monitor. Bitwise OR of + * GPS_GEOFENCE_ENTERED, GPS_GEOFENCE_EXITED and + * GPS_GEOFENCE_UNCERTAIN. + * notification_responsiveness_ms - Defines the best-effort description + * of how soon should the callback be called when the transition + * associated with the Geofence is triggered. For instance, if set + * to 1000 millseconds with GPS_GEOFENCE_ENTERED, the callback + * should be called 1000 milliseconds within entering the geofence. + * This parameter is defined in milliseconds. + * NOTE: This is not to be confused with the rate that the GPS is + * polled at. It is acceptable to dynamically vary the rate of + * sampling the GPS for power-saving reasons; thus the rate of + * sampling may be faster or slower than this. + * unknown_timer_ms - The time limit after which the UNCERTAIN transition + * should be triggered. This parameter is defined in milliseconds. + * See above for a detailed explanation. + */ + void (*add_geofence_area) (int32_t geofence_id, double latitude, double longitude, + double radius_meters, int last_transition, int monitor_transitions, + int notification_responsiveness_ms, int unknown_timer_ms); + + /** + * Pause monitoring a particular geofence. + * Parameters: + * geofence_id - The id for the geofence. + */ + void (*pause_geofence) (int32_t geofence_id); + + /** + * Resume monitoring a particular geofence. + * Parameters: + * geofence_id - The id for the geofence. + * monitor_transitions - Which transitions to monitor. Bitwise OR of + * GPS_GEOFENCE_ENTERED, GPS_GEOFENCE_EXITED and + * GPS_GEOFENCE_UNCERTAIN. + * This supersedes the value associated provided in the + * add_geofence_area call. + */ + void (*resume_geofence) (int32_t geofence_id, int monitor_transitions); + + /** + * Remove a geofence area. After the function returns, no notifications + * should be sent. + * Parameter: + * geofence_id - The id for the geofence. + */ + void (*remove_geofence_area) (int32_t geofence_id); +} GpsGeofencingInterface; + + +/** + * Represents an estimate of the GPS clock time. + */ +typedef struct { + /** set to sizeof(GpsClock) */ + size_t size; + + /** A set of flags indicating the validity of the fields in this data structure. */ + GpsClockFlags flags; + + /** + * Leap second data. + * The sign of the value is defined by the following equation: + * utc_time_ns = time_ns + (full_bias_ns + bias_ns) - leap_second * 1,000,000,000 + * + * If the data is available 'flags' must contain GPS_CLOCK_HAS_LEAP_SECOND. + */ + int16_t leap_second; + + /** + * Indicates the type of time reported by the 'time_ns' field. + * This is a Mandatory field. + */ + GpsClockType type; + + /** + * The GPS receiver internal clock value. This can be either the local hardware clock value + * (GPS_CLOCK_TYPE_LOCAL_HW_TIME), or the current GPS time derived inside GPS receiver + * (GPS_CLOCK_TYPE_GPS_TIME). The field 'type' defines the time reported. + * + * For local hardware clock, this value is expected to be monotonically increasing during + * the reporting session. The real GPS time can be derived by compensating the 'full bias' + * (when it is available) from this value. + * + * For GPS time, this value is expected to be the best estimation of current GPS time that GPS + * receiver can achieve. Set the 'time uncertainty' appropriately when GPS time is specified. + * + * Sub-nanosecond accuracy can be provided by means of the 'bias' field. + * The value contains the 'time uncertainty' in it. + * + * This is a Mandatory field. + */ + int64_t time_ns; + + /** + * 1-Sigma uncertainty associated with the clock's time in nanoseconds. + * The uncertainty is represented as an absolute (single sided) value. + * + * This value should be set if GPS_CLOCK_TYPE_GPS_TIME is set. + * If the data is available 'flags' must contain GPS_CLOCK_HAS_TIME_UNCERTAINTY. + */ + double time_uncertainty_ns; + + /** + * The difference between hardware clock ('time' field) inside GPS receiver and the true GPS + * time since 0000Z, January 6, 1980, in nanoseconds. + * This value is used if and only if GPS_CLOCK_TYPE_LOCAL_HW_TIME is set, and GPS receiver + * has solved the clock for GPS time. + * The caller is responsible for using the 'bias uncertainty' field for quality check. + * + * The sign of the value is defined by the following equation: + * true time (GPS time) = time_ns + (full_bias_ns + bias_ns) + * + * This value contains the 'bias uncertainty' in it. + * If the data is available 'flags' must contain GPS_CLOCK_HAS_FULL_BIAS. + + */ + int64_t full_bias_ns; + + /** + * Sub-nanosecond bias. + * The value contains the 'bias uncertainty' in it. + * + * If the data is available 'flags' must contain GPS_CLOCK_HAS_BIAS. + */ + double bias_ns; + + /** + * 1-Sigma uncertainty associated with the clock's bias in nanoseconds. + * The uncertainty is represented as an absolute (single sided) value. + * + * If the data is available 'flags' must contain GPS_CLOCK_HAS_BIAS_UNCERTAINTY. + */ + double bias_uncertainty_ns; + + /** + * The clock's drift in nanoseconds (per second). + * A positive value means that the frequency is higher than the nominal frequency. + * + * The value contains the 'drift uncertainty' in it. + * If the data is available 'flags' must contain GPS_CLOCK_HAS_DRIFT. + * + * If GpsMeasurement's 'flags' field contains GPS_MEASUREMENT_HAS_UNCORRECTED_PSEUDORANGE_RATE, + * it is encouraged that this field is also provided. + */ + double drift_nsps; + + /** + * 1-Sigma uncertainty associated with the clock's drift in nanoseconds (per second). + * The uncertainty is represented as an absolute (single sided) value. + * + * If the data is available 'flags' must contain GPS_CLOCK_HAS_DRIFT_UNCERTAINTY. + */ + double drift_uncertainty_nsps; +} GpsClock; + +/** + * Represents a GPS Measurement, it contains raw and computed information. + */ +typedef struct { + /** set to sizeof(GpsMeasurement) */ + size_t size; + + /** A set of flags indicating the validity of the fields in this data structure. */ + GpsMeasurementFlags flags; + + /** + * Pseudo-random number in the range of [1, 32] + * This is a Mandatory value. + */ + int8_t prn; + + /** + * Time offset at which the measurement was taken in nanoseconds. + * The reference receiver's time is specified by GpsData::clock::time_ns and should be + * interpreted in the same way as indicated by GpsClock::type. + * + * The sign of time_offset_ns is given by the following equation: + * measurement time = GpsClock::time_ns + time_offset_ns + * + * It provides an individual time-stamp for the measurement, and allows sub-nanosecond accuracy. + * This is a Mandatory value. + */ + double time_offset_ns; + + /** + * Per satellite sync state. It represents the current sync state for the associated satellite. + * Based on the sync state, the 'received GPS tow' field should be interpreted accordingly. + * + * This is a Mandatory value. + */ + GpsMeasurementState state; + + /** + * Received GPS Time-of-Week at the measurement time, in nanoseconds. + * The value is relative to the beginning of the current GPS week. + * + * Given the highest sync state that can be achieved, per each satellite, valid range for + * this field can be: + * Searching : [ 0 ] : GPS_MEASUREMENT_STATE_UNKNOWN + * C/A code lock : [ 0 1ms ] : GPS_MEASUREMENT_STATE_CODE_LOCK is set + * Bit sync : [ 0 20ms ] : GPS_MEASUREMENT_STATE_BIT_SYNC is set + * Subframe sync : [ 0 6s ] : GPS_MEASUREMENT_STATE_SUBFRAME_SYNC is set + * TOW decoded : [ 0 1week ] : GPS_MEASUREMENT_STATE_TOW_DECODED is set + * + * However, if there is any ambiguity in integer millisecond, + * GPS_MEASUREMENT_STATE_MSEC_AMBIGUOUS should be set accordingly, in the 'state' field. + * + * This value must be populated if 'state' != GPS_MEASUREMENT_STATE_UNKNOWN. + */ + int64_t received_gps_tow_ns; + + /** + * 1-Sigma uncertainty of the Received GPS Time-of-Week in nanoseconds. + * + * This value must be populated if 'state' != GPS_MEASUREMENT_STATE_UNKNOWN. + */ + int64_t received_gps_tow_uncertainty_ns; + + /** + * Carrier-to-noise density in dB-Hz, in the range [0, 63]. + * It contains the measured C/N0 value for the signal at the antenna input. + * + * This is a Mandatory value. + */ + double c_n0_dbhz; + + /** + * Pseudorange rate at the timestamp in m/s. + * The correction of a given Pseudorange Rate value includes corrections for receiver and + * satellite clock frequency errors. + * + * If GPS_MEASUREMENT_HAS_UNCORRECTED_PSEUDORANGE_RATE is set in 'flags' field, this field must + * be populated with the 'uncorrected' reading. + * If GPS_MEASUREMENT_HAS_UNCORRECTED_PSEUDORANGE_RATE is not set in 'flags' field, this field + * must be populated with the 'corrected' reading. This is the default behavior. + * + * It is encouraged to provide the 'uncorrected' 'pseudorange rate', and provide GpsClock's + * 'drift' field as well. + * + * The value includes the 'pseudorange rate uncertainty' in it. + * A positive 'uncorrected' value indicates that the SV is moving away from the receiver. + * + * The sign of the 'uncorrected' 'pseudorange rate' and its relation to the sign of 'doppler + * shift' is given by the equation: + * pseudorange rate = -k * doppler shift (where k is a constant) + * + * This is a Mandatory value. + */ + double pseudorange_rate_mps; + + /** + * 1-Sigma uncertainty of the pseudurange rate in m/s. + * The uncertainty is represented as an absolute (single sided) value. + * + * This is a Mandatory value. + */ + double pseudorange_rate_uncertainty_mps; + + /** + * Accumulated delta range's state. It indicates whether ADR is reset or there is a cycle slip + * (indicating loss of lock). + * + * This is a Mandatory value. + */ + GpsAccumulatedDeltaRangeState accumulated_delta_range_state; + + /** + * Accumulated delta range since the last channel reset in meters. + * A positive value indicates that the SV is moving away from the receiver. + * + * The sign of the 'accumulated delta range' and its relation to the sign of 'carrier phase' + * is given by the equation: + * accumulated delta range = -k * carrier phase (where k is a constant) + * + * This value must be populated if 'accumulated delta range state' != GPS_ADR_STATE_UNKNOWN. + * However, it is expected that the data is only accurate when: + * 'accumulated delta range state' == GPS_ADR_STATE_VALID. + */ + double accumulated_delta_range_m; + + /** + * 1-Sigma uncertainty of the accumulated delta range in meters. + * This value must be populated if 'accumulated delta range state' != GPS_ADR_STATE_UNKNOWN. + */ + double accumulated_delta_range_uncertainty_m; + + /** + * Best derived Pseudorange by the chip-set, in meters. + * The value contains the 'pseudorange uncertainty' in it. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_PSEUDORANGE. + */ + double pseudorange_m; + + /** + * 1-Sigma uncertainty of the pseudorange in meters. + * The value contains the 'pseudorange' and 'clock' uncertainty in it. + * The uncertainty is represented as an absolute (single sided) value. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_PSEUDORANGE_UNCERTAINTY. + */ + double pseudorange_uncertainty_m; + + /** + * A fraction of the current C/A code cycle, in the range [0.0, 1023.0] + * This value contains the time (in Chip units) since the last C/A code cycle (GPS Msec epoch). + * + * The reference frequency is given by the field 'carrier_frequency_hz'. + * The value contains the 'code-phase uncertainty' in it. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CODE_PHASE. + */ + double code_phase_chips; + + /** + * 1-Sigma uncertainty of the code-phase, in a fraction of chips. + * The uncertainty is represented as an absolute (single sided) value. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CODE_PHASE_UNCERTAINTY. + */ + double code_phase_uncertainty_chips; + + /** + * Carrier frequency at which codes and messages are modulated, it can be L1 or L2. + * If the field is not set, the carrier frequency is assumed to be L1. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CARRIER_FREQUENCY. + */ + float carrier_frequency_hz; + + /** + * The number of full carrier cycles between the satellite and the receiver. + * The reference frequency is given by the field 'carrier_frequency_hz'. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CARRIER_CYCLES. + */ + int64_t carrier_cycles; + + /** + * The RF phase detected by the receiver, in the range [0.0, 1.0]. + * This is usually the fractional part of the complete carrier phase measurement. + * + * The reference frequency is given by the field 'carrier_frequency_hz'. + * The value contains the 'carrier-phase uncertainty' in it. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CARRIER_PHASE. + */ + double carrier_phase; + + /** + * 1-Sigma uncertainty of the carrier-phase. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_CARRIER_PHASE_UNCERTAINTY. + */ + double carrier_phase_uncertainty; + + /** + * An enumeration that indicates the 'loss of lock' state of the event. + */ + GpsLossOfLock loss_of_lock; + + /** + * The number of GPS bits transmitted since Sat-Sun midnight (GPS week). + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_BIT_NUMBER. + */ + int32_t bit_number; + + /** + * The elapsed time since the last received bit in milliseconds, in the range [0, 20] + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_TIME_FROM_LAST_BIT. + */ + int16_t time_from_last_bit_ms; + + /** + * Doppler shift in Hz. + * A positive value indicates that the SV is moving toward the receiver. + * + * The reference frequency is given by the field 'carrier_frequency_hz'. + * The value contains the 'doppler shift uncertainty' in it. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_DOPPLER_SHIFT. + */ + double doppler_shift_hz; + + /** + * 1-Sigma uncertainty of the doppler shift in Hz. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_DOPPLER_SHIFT_UNCERTAINTY. + */ + double doppler_shift_uncertainty_hz; + + /** + * An enumeration that indicates the 'multipath' state of the event. + */ + GpsMultipathIndicator multipath_indicator; + + /** + * Signal-to-noise ratio in dB. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_SNR. + */ + double snr_db; + + /** + * Elevation in degrees, the valid range is [-90, 90]. + * The value contains the 'elevation uncertainty' in it. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_ELEVATION. + */ + double elevation_deg; + + /** + * 1-Sigma uncertainty of the elevation in degrees, the valid range is [0, 90]. + * The uncertainty is represented as the absolute (single sided) value. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_ELEVATION_UNCERTAINTY. + */ + double elevation_uncertainty_deg; + + /** + * Azimuth in degrees, in the range [0, 360). + * The value contains the 'azimuth uncertainty' in it. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_AZIMUTH. + * */ + double azimuth_deg; + + /** + * 1-Sigma uncertainty of the azimuth in degrees, the valid range is [0, 180]. + * The uncertainty is represented as an absolute (single sided) value. + * + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_AZIMUTH_UNCERTAINTY. + */ + double azimuth_uncertainty_deg; + + /** + * Whether the GPS represented by the measurement was used for computing the most recent fix. + * If the data is available, 'flags' must contain GPS_MEASUREMENT_HAS_USED_IN_FIX. + */ + bool used_in_fix; +} GpsMeasurement; + +/** Represents a reading of GPS measurements. */ +typedef struct { + /** set to sizeof(GpsData) */ + size_t size; + + /** Number of measurements. */ + size_t measurement_count; + + /** The array of measurements. */ + GpsMeasurement measurements[GPS_MAX_MEASUREMENT]; + + /** The GPS clock time reading. */ + GpsClock clock; +} GpsData; + +/** + * The callback for to report measurements from the HAL. + * + * Parameters: + * data - A data structure containing the measurements. + */ +typedef void (*gps_measurement_callback) (GpsData* data); + +typedef struct { + /** set to sizeof(GpsMeasurementCallbacks) */ + size_t size; + gps_measurement_callback measurement_callback; +} GpsMeasurementCallbacks; + +#define GPS_MEASUREMENT_OPERATION_SUCCESS 0 +#define GPS_MEASUREMENT_ERROR_ALREADY_INIT -100 +#define GPS_MEASUREMENT_ERROR_GENERIC -101 + +/** + * Extended interface for GPS Measurements support. + */ +typedef struct { + /** Set to sizeof(GpsMeasurementInterface) */ + size_t size; + + /** + * Initializes the interface and registers the callback routines with the HAL. + * After a successful call to 'init' the HAL must begin to provide updates at its own phase. + * + * Status: + * GPS_MEASUREMENT_OPERATION_SUCCESS + * GPS_MEASUREMENT_ERROR_ALREADY_INIT - if a callback has already been registered without a + * corresponding call to 'close' + * GPS_MEASUREMENT_ERROR_GENERIC - if any other error occurred, it is expected that the HAL + * will not generate any updates upon returning this error code. + */ + int (*init) (GpsMeasurementCallbacks* callbacks); + + /** + * Stops updates from the HAL, and unregisters the callback routines. + * After a call to stop, the previously registered callbacks must be considered invalid by the + * HAL. + * If stop is invoked without a previous 'init', this function should perform no work. + */ + void (*close) (); + +} GpsMeasurementInterface; + + +/** Represents a GPS navigation message (or a fragment of it). */ +typedef struct { + /** set to sizeof(GpsNavigationMessage) */ + size_t size; + + /** + * Pseudo-random number in the range of [1, 32] + * This is a Mandatory value. + */ + int8_t prn; + + /** + * The type of message contained in the structure. + * This is a Mandatory value. + */ + GpsNavigationMessageType type; + + /** + * The status of the received navigation message. + * No need to send any navigation message that contains words with parity error and cannot be + * corrected. + */ + NavigationMessageStatus status; + + /** + * Message identifier. + * It provides an index so the complete Navigation Message can be assembled. i.e. fo L1 C/A + * subframe 4 and 5, this value corresponds to the 'frame id' of the navigation message. + * Subframe 1, 2, 3 does not contain a 'frame id' and this value can be set to -1. + */ + int16_t message_id; + + /** + * Sub-message identifier. + * If required by the message 'type', this value contains a sub-index within the current + * message (or frame) that is being transmitted. + * i.e. for L1 C/A the submessage id corresponds to the sub-frame id of the navigation message. + */ + int16_t submessage_id; + + /** + * The length of the data (in bytes) contained in the current message. + * If this value is different from zero, 'data' must point to an array of the same size. + * e.g. for L1 C/A the size of the sub-frame will be 40 bytes (10 words, 30 bits/word). + * + * This is a Mandatory value. + */ + size_t data_length; + + /** + * The data of the reported GPS message. + * The bytes (or words) specified using big endian format (MSB first). + * + * For L1 C/A, each subframe contains 10 30-bit GPS words. Each GPS word (30 bits) should be + * fitted into the last 30 bits in a 4-byte word (skip B31 and B32), with MSB first. + */ + uint8_t* data; + +} GpsNavigationMessage; + +/** + * The callback to report an available fragment of a GPS navigation messages from the HAL. + * + * Parameters: + * message - The GPS navigation submessage/subframe representation. + */ +typedef void (*gps_navigation_message_callback) (GpsNavigationMessage* message); + +typedef struct { + /** set to sizeof(GpsNavigationMessageCallbacks) */ + size_t size; + gps_navigation_message_callback navigation_message_callback; +} GpsNavigationMessageCallbacks; + +#define GPS_NAVIGATION_MESSAGE_OPERATION_SUCCESS 0 +#define GPS_NAVIGATION_MESSAGE_ERROR_ALREADY_INIT -100 +#define GPS_NAVIGATION_MESSAGE_ERROR_GENERIC -101 + +/** + * Extended interface for GPS navigation message reporting support. + */ +typedef struct { + /** Set to sizeof(GpsNavigationMessageInterface) */ + size_t size; + + /** + * Initializes the interface and registers the callback routines with the HAL. + * After a successful call to 'init' the HAL must begin to provide updates as they become + * available. + * + * Status: + * GPS_NAVIGATION_MESSAGE_OPERATION_SUCCESS + * GPS_NAVIGATION_MESSAGE_ERROR_ALREADY_INIT - if a callback has already been registered + * without a corresponding call to 'close'. + * GPS_NAVIGATION_MESSAGE_ERROR_GENERIC - if any other error occurred, it is expected that + * the HAL will not generate any updates upon returning this error code. + */ + int (*init) (GpsNavigationMessageCallbacks* callbacks); + + /** + * Stops updates from the HAL, and unregisters the callback routines. + * After a call to stop, the previously registered callbacks must be considered invalid by the + * HAL. + * If stop is invoked without a previous 'init', this function should perform no work. + */ + void (*close) (); + +} GpsNavigationMessageInterface; + +/** + * Interface for passing GNSS configuration contents from platform to HAL. + */ +typedef struct { + /** Set to sizeof(GnssConfigurationInterface) */ + size_t size; + + /** + * Deliver GNSS configuration contents to HAL. + * Parameters: + * config_data - a pointer to a char array which holds what usually is expected from + file(/etc/gps.conf), i.e., a sequence of UTF8 strings separated by '\n'. + * length - total number of UTF8 characters in configuraiton data. + * + * IMPORTANT: + * GPS HAL should expect this function can be called multiple times. And it may be + * called even when GpsLocationProvider is already constructed and enabled. GPS HAL + * should maintain the existing requests for various callback regardless the change + * in configuration data. + */ + void (*configuration_update) (const char* config_data, int32_t length); +} GnssConfigurationInterface; + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_GPS_H */ + diff --git a/third_party/android_hardware_libhardware/include/hardware/gralloc.h b/third_party/android_hardware_libhardware/include/hardware/gralloc.h new file mode 100644 index 00000000000000..07ac0290b45bdd --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/gralloc.h @@ -0,0 +1,401 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_GRALLOC_INTERFACE_H +#define ANDROID_GRALLOC_INTERFACE_H + +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include + +__BEGIN_DECLS + +/** + * Module versioning information for the Gralloc hardware module, based on + * gralloc_module_t.common.module_api_version. + * + * Version History: + * + * GRALLOC_MODULE_API_VERSION_0_1: + * Initial Gralloc hardware module API. + * + * GRALLOC_MODULE_API_VERSION_0_2: + * Add support for flexible YCbCr format with (*lock_ycbcr)() method. + * + * GRALLOC_MODULE_API_VERSION_0_3: + * Add support for fence passing to/from lock/unlock. + */ + +#define GRALLOC_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) +#define GRALLOC_MODULE_API_VERSION_0_2 HARDWARE_MODULE_API_VERSION(0, 2) +#define GRALLOC_MODULE_API_VERSION_0_3 HARDWARE_MODULE_API_VERSION(0, 3) + +#define GRALLOC_DEVICE_API_VERSION_0_1 HARDWARE_DEVICE_API_VERSION(0, 1) + +/** + * The id of this module + */ +#define GRALLOC_HARDWARE_MODULE_ID "gralloc" + +/** + * Name of the graphics device to open + */ + +#define GRALLOC_HARDWARE_GPU0 "gpu0" + +enum { + /* buffer is never read in software */ + GRALLOC_USAGE_SW_READ_NEVER = 0x00000000, + /* buffer is rarely read in software */ + GRALLOC_USAGE_SW_READ_RARELY = 0x00000002, + /* buffer is often read in software */ + GRALLOC_USAGE_SW_READ_OFTEN = 0x00000003, + /* mask for the software read values */ + GRALLOC_USAGE_SW_READ_MASK = 0x0000000F, + + /* buffer is never written in software */ + GRALLOC_USAGE_SW_WRITE_NEVER = 0x00000000, + /* buffer is rarely written in software */ + GRALLOC_USAGE_SW_WRITE_RARELY = 0x00000020, + /* buffer is often written in software */ + GRALLOC_USAGE_SW_WRITE_OFTEN = 0x00000030, + /* mask for the software write values */ + GRALLOC_USAGE_SW_WRITE_MASK = 0x000000F0, + + /* buffer will be used as an OpenGL ES texture */ + GRALLOC_USAGE_HW_TEXTURE = 0x00000100, + /* buffer will be used as an OpenGL ES render target */ + GRALLOC_USAGE_HW_RENDER = 0x00000200, + /* buffer will be used by the 2D hardware blitter */ + GRALLOC_USAGE_HW_2D = 0x00000400, + /* buffer will be used by the HWComposer HAL module */ + GRALLOC_USAGE_HW_COMPOSER = 0x00000800, + /* buffer will be used with the framebuffer device */ + GRALLOC_USAGE_HW_FB = 0x00001000, + + /* buffer should be displayed full-screen on an external display when + * possible */ + GRALLOC_USAGE_EXTERNAL_DISP = 0x00002000, + + /* Must have a hardware-protected path to external display sink for + * this buffer. If a hardware-protected path is not available, then + * either don't composite only this buffer (preferred) to the + * external sink, or (less desirable) do not route the entire + * composition to the external sink. */ + GRALLOC_USAGE_PROTECTED = 0x00004000, + + /* buffer may be used as a cursor */ + GRALLOC_USAGE_CURSOR = 0x00008000, + + /* buffer will be used with the HW video encoder */ + GRALLOC_USAGE_HW_VIDEO_ENCODER = 0x00010000, + /* buffer will be written by the HW camera pipeline */ + GRALLOC_USAGE_HW_CAMERA_WRITE = 0x00020000, + /* buffer will be read by the HW camera pipeline */ + GRALLOC_USAGE_HW_CAMERA_READ = 0x00040000, + /* buffer will be used as part of zero-shutter-lag queue */ + GRALLOC_USAGE_HW_CAMERA_ZSL = 0x00060000, + /* mask for the camera access values */ + GRALLOC_USAGE_HW_CAMERA_MASK = 0x00060000, + /* mask for the software usage bit-mask */ + GRALLOC_USAGE_HW_MASK = 0x00071F00, + + /* buffer will be used as a RenderScript Allocation */ + GRALLOC_USAGE_RENDERSCRIPT = 0x00100000, + + /* Set by the consumer to indicate to the producer that they may attach a + * buffer that they did not detach from the BufferQueue. Will be filtered + * out by GRALLOC_USAGE_ALLOC_MASK, so gralloc modules will not need to + * handle this flag. */ + GRALLOC_USAGE_FOREIGN_BUFFERS = 0x00200000, + + /* Mask of all flags which could be passed to a gralloc module for buffer + * allocation. Any flags not in this mask do not need to be handled by + * gralloc modules. */ + GRALLOC_USAGE_ALLOC_MASK = ~(GRALLOC_USAGE_FOREIGN_BUFFERS), + + /* implementation-specific private usage flags */ + GRALLOC_USAGE_PRIVATE_0 = 0x10000000, + GRALLOC_USAGE_PRIVATE_1 = 0x20000000, + GRALLOC_USAGE_PRIVATE_2 = 0x40000000, + GRALLOC_USAGE_PRIVATE_3 = 0x80000000, + GRALLOC_USAGE_PRIVATE_MASK = 0xF0000000, + +#ifdef EXYNOS4_ENHANCEMENTS + /* SAMSUNG */ + GRALLOC_USAGE_PRIVATE_NONECACHE = 0x00800000, + + GRALLOC_USAGE_HW_FIMC1 = 0x01000000, + GRALLOC_USAGE_HW_ION = 0x02000000, + GRALLOC_USAGE_YUV_ADDR = 0x04000000, + GRALLOC_USAGE_CAMERA = 0x08000000, + + /* SEC Private usage , for Overlay path at HWC */ + GRALLOC_USAGE_HWC_HWOVERLAY = 0x20000000, +#endif +}; + +/*****************************************************************************/ + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct gralloc_module_t { + struct hw_module_t common; + + /* + * (*registerBuffer)() must be called before a buffer_handle_t that has not + * been created with (*alloc_device_t::alloc)() can be used. + * + * This is intended to be used with buffer_handle_t's that have been + * received in this process through IPC. + * + * This function checks that the handle is indeed a valid one and prepares + * it for use with (*lock)() and (*unlock)(). + * + * It is not necessary to call (*registerBuffer)() on a handle created + * with (*alloc_device_t::alloc)(). + * + * returns an error if this buffer_handle_t is not valid. + */ + int (*registerBuffer)(struct gralloc_module_t const* module, + buffer_handle_t handle); + + /* + * (*unregisterBuffer)() is called once this handle is no longer needed in + * this process. After this call, it is an error to call (*lock)(), + * (*unlock)(), or (*registerBuffer)(). + * + * This function doesn't close or free the handle itself; this is done + * by other means, usually through libcutils's native_handle_close() and + * native_handle_free(). + * + * It is an error to call (*unregisterBuffer)() on a buffer that wasn't + * explicitly registered first. + */ + int (*unregisterBuffer)(struct gralloc_module_t const* module, + buffer_handle_t handle); + + /* + * The (*lock)() method is called before a buffer is accessed for the + * specified usage. This call may block, for instance if the h/w needs + * to finish rendering or if CPU caches need to be synchronized. + * + * The caller promises to modify only pixels in the area specified + * by (l,t,w,h). + * + * The content of the buffer outside of the specified area is NOT modified + * by this call. + * + * If usage specifies GRALLOC_USAGE_SW_*, vaddr is filled with the address + * of the buffer in virtual memory. + * + * Note calling (*lock)() on HAL_PIXEL_FORMAT_YCbCr_*_888 buffers will fail + * and return -EINVAL. These buffers must be locked with (*lock_ycbcr)() + * instead. + * + * THREADING CONSIDERATIONS: + * + * It is legal for several different threads to lock a buffer from + * read access, none of the threads are blocked. + * + * However, locking a buffer simultaneously for write or read/write is + * undefined, but: + * - shall not result in termination of the process + * - shall not block the caller + * It is acceptable to return an error or to leave the buffer's content + * into an indeterminate state. + * + * If the buffer was created with a usage mask incompatible with the + * requested usage flags here, -EINVAL is returned. + * + */ + + int (*lock)(struct gralloc_module_t const* module, + buffer_handle_t handle, int usage, + int l, int t, int w, int h, + void** vaddr); + + + /* + * The (*unlock)() method must be called after all changes to the buffer + * are completed. + */ + + int (*unlock)(struct gralloc_module_t const* module, + buffer_handle_t handle); + +#ifdef EXYNOS4_ENHANCEMENTS + int (*getphys) (struct gralloc_module_t const* module, + buffer_handle_t handle, void** paddr); +#endif + + /* reserved for future use */ + int (*perform)(struct gralloc_module_t const* module, + int operation, ... ); + + /* + * The (*lock_ycbcr)() method is like the (*lock)() method, with the + * difference that it fills a struct ycbcr with a description of the buffer + * layout, and zeroes out the reserved fields. + * + * If the buffer format is not compatible with a flexible YUV format (e.g. + * the buffer layout cannot be represented with the ycbcr struct), it + * will return -EINVAL. + * + * This method must work on buffers with HAL_PIXEL_FORMAT_YCbCr_*_888 + * if supported by the device, as well as with any other format that is + * requested by the multimedia codecs when they are configured with a + * flexible-YUV-compatible color-format with android native buffers. + * + * Note that this method may also be called on buffers of other formats, + * including non-YUV formats. + * + * Added in GRALLOC_MODULE_API_VERSION_0_2. + */ + + int (*lock_ycbcr)(struct gralloc_module_t const* module, + buffer_handle_t handle, int usage, + int l, int t, int w, int h, + struct android_ycbcr *ycbcr); + + /* + * The (*lockAsync)() method is like the (*lock)() method except + * that the buffer's sync fence object is passed into the lock + * call instead of requiring the caller to wait for completion. + * + * The gralloc implementation takes ownership of the fenceFd and + * is responsible for closing it when no longer needed. + * + * Added in GRALLOC_MODULE_API_VERSION_0_3. + */ + int (*lockAsync)(struct gralloc_module_t const* module, + buffer_handle_t handle, int usage, + int l, int t, int w, int h, + void** vaddr, int fenceFd); + + /* + * The (*unlockAsync)() method is like the (*unlock)() method + * except that a buffer sync fence object is returned from the + * lock call, representing the completion of any pending work + * performed by the gralloc implementation. + * + * The caller takes ownership of the fenceFd and is responsible + * for closing it when no longer needed. + * + * Added in GRALLOC_MODULE_API_VERSION_0_3. + */ + int (*unlockAsync)(struct gralloc_module_t const* module, + buffer_handle_t handle, int* fenceFd); + + /* + * The (*lockAsync_ycbcr)() method is like the (*lock_ycbcr)() + * method except that the buffer's sync fence object is passed + * into the lock call instead of requiring the caller to wait for + * completion. + * + * The gralloc implementation takes ownership of the fenceFd and + * is responsible for closing it when no longer needed. + * + * Added in GRALLOC_MODULE_API_VERSION_0_3. + */ + int (*lockAsync_ycbcr)(struct gralloc_module_t const* module, + buffer_handle_t handle, int usage, + int l, int t, int w, int h, + struct android_ycbcr *ycbcr, int fenceFd); + + /* reserved for future use */ + void* reserved_proc[3]; +} gralloc_module_t; + +/*****************************************************************************/ + +/** + * Every device data structure must begin with hw_device_t + * followed by module specific public methods and attributes. + */ + +typedef struct alloc_device_t { + struct hw_device_t common; + + /* + * (*alloc)() Allocates a buffer in graphic memory with the requested + * parameters and returns a buffer_handle_t and the stride in pixels to + * allow the implementation to satisfy hardware constraints on the width + * of a pixmap (eg: it may have to be multiple of 8 pixels). + * The CALLER TAKES OWNERSHIP of the buffer_handle_t. + * + * If format is HAL_PIXEL_FORMAT_YCbCr_420_888, the returned stride must be + * 0, since the actual strides are available from the android_ycbcr + * structure. + * + * Returns 0 on success or -errno on error. + */ + + int (*alloc)(struct alloc_device_t* dev, + int w, int h, int format, int usage, + buffer_handle_t* handle, int* stride); + + /* + * (*free)() Frees a previously allocated buffer. + * Behavior is undefined if the buffer is still mapped in any process, + * but shall not result in termination of the program or security breaches + * (allowing a process to get access to another process' buffers). + * THIS FUNCTION TAKES OWNERSHIP of the buffer_handle_t which becomes + * invalid after the call. + * + * Returns 0 on success or -errno on error. + */ + int (*free)(struct alloc_device_t* dev, + buffer_handle_t handle); + + /* This hook is OPTIONAL. + * + * If non NULL it will be caused by SurfaceFlinger on dumpsys + */ + void (*dump)(struct alloc_device_t *dev, char *buff, int buff_len); + + void* reserved_proc[7]; +} alloc_device_t; + + +/** convenience API for opening and closing a supported device */ + +static inline int gralloc_open(const struct hw_module_t* module, + struct alloc_device_t** device) { + return module->methods->open(module, + GRALLOC_HARDWARE_GPU0, (struct hw_device_t**)device); +} + +static inline int gralloc_close(struct alloc_device_t* device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_GRALLOC_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/hardware.h b/third_party/android_hardware_libhardware/include/hardware/hardware.h new file mode 100644 index 00000000000000..74f57aa4c28fb3 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/hardware.h @@ -0,0 +1,238 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_HARDWARE_H +#define ANDROID_INCLUDE_HARDWARE_HARDWARE_H + +#include +#include + +#include +#include + +__BEGIN_DECLS + +/* + * Value for the hw_module_t.tag field + */ + +#define MAKE_TAG_CONSTANT(A,B,C,D) (((A) << 24) | ((B) << 16) | ((C) << 8) | (D)) + +#define HARDWARE_MODULE_TAG MAKE_TAG_CONSTANT('H', 'W', 'M', 'T') +#define HARDWARE_DEVICE_TAG MAKE_TAG_CONSTANT('H', 'W', 'D', 'T') + +#define HARDWARE_MAKE_API_VERSION(maj,min) \ + ((((maj) & 0xff) << 8) | ((min) & 0xff)) + +#define HARDWARE_MAKE_API_VERSION_2(maj,min,hdr) \ + ((((maj) & 0xff) << 24) | (((min) & 0xff) << 16) | ((hdr) & 0xffff)) +#define HARDWARE_API_VERSION_2_MAJ_MIN_MASK 0xffff0000 +#define HARDWARE_API_VERSION_2_HEADER_MASK 0x0000ffff + + +/* + * The current HAL API version. + * + * All module implementations must set the hw_module_t.hal_api_version field + * to this value when declaring the module with HAL_MODULE_INFO_SYM. + * + * Note that previous implementations have always set this field to 0. + * Therefore, libhardware HAL API will always consider versions 0.0 and 1.0 + * to be 100% binary compatible. + * + */ +#define HARDWARE_HAL_API_VERSION HARDWARE_MAKE_API_VERSION(1, 0) + +/* + * Helper macros for module implementors. + * + * The derived modules should provide convenience macros for supported + * versions so that implementations can explicitly specify module/device + * versions at definition time. + * + * Use this macro to set the hw_module_t.module_api_version field. + */ +#define HARDWARE_MODULE_API_VERSION(maj,min) HARDWARE_MAKE_API_VERSION(maj,min) +#define HARDWARE_MODULE_API_VERSION_2(maj,min,hdr) HARDWARE_MAKE_API_VERSION_2(maj,min,hdr) + +/* + * Use this macro to set the hw_device_t.version field + */ +#define HARDWARE_DEVICE_API_VERSION(maj,min) HARDWARE_MAKE_API_VERSION(maj,min) +#define HARDWARE_DEVICE_API_VERSION_2(maj,min,hdr) HARDWARE_MAKE_API_VERSION_2(maj,min,hdr) + +struct hw_module_t; +struct hw_module_methods_t; +struct hw_device_t; + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct hw_module_t { + /** tag must be initialized to HARDWARE_MODULE_TAG */ + uint32_t tag; + + /** + * The API version of the implemented module. The module owner is + * responsible for updating the version when a module interface has + * changed. + * + * The derived modules such as gralloc and audio own and manage this field. + * The module user must interpret the version field to decide whether or + * not to inter-operate with the supplied module implementation. + * For example, SurfaceFlinger is responsible for making sure that + * it knows how to manage different versions of the gralloc-module API, + * and AudioFlinger must know how to do the same for audio-module API. + * + * The module API version should include a major and a minor component. + * For example, version 1.0 could be represented as 0x0100. This format + * implies that versions 0x0100-0x01ff are all API-compatible. + * + * In the future, libhardware will expose a hw_get_module_version() + * (or equivalent) function that will take minimum/maximum supported + * versions as arguments and would be able to reject modules with + * versions outside of the supplied range. + */ + uint16_t module_api_version; +#define version_major module_api_version + /** + * version_major/version_minor defines are supplied here for temporary + * source code compatibility. They will be removed in the next version. + * ALL clients must convert to the new version format. + */ + + /** + * The API version of the HAL module interface. This is meant to + * version the hw_module_t, hw_module_methods_t, and hw_device_t + * structures and definitions. + * + * The HAL interface owns this field. Module users/implementations + * must NOT rely on this value for version information. + * + * Presently, 0 is the only valid value. + */ + uint16_t hal_api_version; +#define version_minor hal_api_version + + /** Identifier of module */ + const char *id; + + /** Name of this module */ + const char *name; + + /** Author/owner/implementor of the module */ + const char *author; + + /** Modules methods */ + struct hw_module_methods_t* methods; + + /** module's dso */ + void* dso; + +#ifdef __LP64__ + uint64_t reserved[32-7]; +#else + /** padding to 128 bytes, reserved for future use */ + uint32_t reserved[32-7]; +#endif + +} hw_module_t; + +typedef struct hw_module_methods_t { + /** Open a specific device */ + int (*open)(const struct hw_module_t* module, const char* id, + struct hw_device_t** device); + +} hw_module_methods_t; + +/** + * Every device data structure must begin with hw_device_t + * followed by module specific public methods and attributes. + */ +typedef struct hw_device_t { + /** tag must be initialized to HARDWARE_DEVICE_TAG */ + uint32_t tag; + + /** + * Version of the module-specific device API. This value is used by + * the derived-module user to manage different device implementations. + * + * The module user is responsible for checking the module_api_version + * and device version fields to ensure that the user is capable of + * communicating with the specific module implementation. + * + * One module can support multiple devices with different versions. This + * can be useful when a device interface changes in an incompatible way + * but it is still necessary to support older implementations at the same + * time. One such example is the Camera 2.0 API. + * + * This field is interpreted by the module user and is ignored by the + * HAL interface itself. + */ + uint32_t version; + + /** reference to the module this device belongs to */ + struct hw_module_t* module; + + /** padding reserved for future use */ +#ifdef __LP64__ + uint64_t reserved[12]; +#else + uint32_t reserved[12]; +#endif + + /** Close this device */ + int (*close)(struct hw_device_t* device); + +} hw_device_t; + +/** + * Name of the hal_module_info + */ +#define HAL_MODULE_INFO_SYM HMI + +/** + * Name of the hal_module_info as a string + */ +#define HAL_MODULE_INFO_SYM_AS_STR "HMI" + +/** + * Get the module info associated with a module by id. + * + * @return: 0 == success, <0 == error and *module == NULL + */ +int hw_get_module(const char *id, const struct hw_module_t **module); + +/** + * Get the module info associated with a module instance by class 'class_id' + * and instance 'inst'. + * + * Some modules types necessitate multiple instances. For example audio supports + * multiple concurrent interfaces and thus 'audio' is the module class + * and 'primary' or 'a2dp' are module interfaces. This implies that the files + * providing these modules would be named audio.primary..so and + * audio.a2dp..so + * + * @return: 0 == success, <0 == error and *module == NULL + */ +int hw_get_module_by_class(const char *class_id, const char *inst, + const struct hw_module_t **module); + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_HARDWARE_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/hdmi_cec.h b/third_party/android_hardware_libhardware/include/hardware/hdmi_cec.h new file mode 100644 index 00000000000000..ab70f92e2b6c06 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/hdmi_cec.h @@ -0,0 +1,429 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_HDMI_CEC_H +#define ANDROID_INCLUDE_HARDWARE_HDMI_CEC_H + +#include +#include + +#include + +__BEGIN_DECLS + +#define HDMI_CEC_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define HDMI_CEC_MODULE_API_VERSION_CURRENT HDMI_MODULE_API_VERSION_1_0 + +#define HDMI_CEC_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define HDMI_CEC_DEVICE_API_VERSION_CURRENT HDMI_DEVICE_API_VERSION_1_0 + +#define HDMI_CEC_HARDWARE_MODULE_ID "hdmi_cec" +#define HDMI_CEC_HARDWARE_INTERFACE "hdmi_cec_hw_if" + +typedef enum cec_device_type { + CEC_DEVICE_INACTIVE = -1, + CEC_DEVICE_TV = 0, + CEC_DEVICE_RECORDER = 1, + CEC_DEVICE_RESERVED = 2, + CEC_DEVICE_TUNER = 3, + CEC_DEVICE_PLAYBACK = 4, + CEC_DEVICE_AUDIO_SYSTEM = 5, + CEC_DEVICE_MAX = CEC_DEVICE_AUDIO_SYSTEM +} cec_device_type_t; + +typedef enum cec_logical_address { + CEC_ADDR_TV = 0, + CEC_ADDR_RECORDER_1 = 1, + CEC_ADDR_RECORDER_2 = 2, + CEC_ADDR_TUNER_1 = 3, + CEC_ADDR_PLAYBACK_1 = 4, + CEC_ADDR_AUDIO_SYSTEM = 5, + CEC_ADDR_TUNER_2 = 6, + CEC_ADDR_TUNER_3 = 7, + CEC_ADDR_PLAYBACK_2 = 8, + CEC_ADDR_RECORDER_3 = 9, + CEC_ADDR_TUNER_4 = 10, + CEC_ADDR_PLAYBACK_3 = 11, + CEC_ADDR_RESERVED_1 = 12, + CEC_ADDR_RESERVED_2 = 13, + CEC_ADDR_FREE_USE = 14, + CEC_ADDR_UNREGISTERED = 15, + CEC_ADDR_BROADCAST = 15 +} cec_logical_address_t; + +/* + * HDMI CEC messages + */ +enum cec_message_type { + CEC_MESSAGE_FEATURE_ABORT = 0x00, + CEC_MESSAGE_IMAGE_VIEW_ON = 0x04, + CEC_MESSAGE_TUNER_STEP_INCREMENT = 0x05, + CEC_MESSAGE_TUNER_STEP_DECREMENT = 0x06, + CEC_MESSAGE_TUNER_DEVICE_STATUS = 0x07, + CEC_MESSAGE_GIVE_TUNER_DEVICE_STATUS = 0x08, + CEC_MESSAGE_RECORD_ON = 0x09, + CEC_MESSAGE_RECORD_STATUS = 0x0A, + CEC_MESSAGE_RECORD_OFF = 0x0B, + CEC_MESSAGE_TEXT_VIEW_ON = 0x0D, + CEC_MESSAGE_RECORD_TV_SCREEN = 0x0F, + CEC_MESSAGE_GIVE_DECK_STATUS = 0x1A, + CEC_MESSAGE_DECK_STATUS = 0x1B, + CEC_MESSAGE_SET_MENU_LANGUAGE = 0x32, + CEC_MESSAGE_CLEAR_ANALOG_TIMER = 0x33, + CEC_MESSAGE_SET_ANALOG_TIMER = 0x34, + CEC_MESSAGE_TIMER_STATUS = 0x35, + CEC_MESSAGE_STANDBY = 0x36, + CEC_MESSAGE_PLAY = 0x41, + CEC_MESSAGE_DECK_CONTROL = 0x42, + CEC_MESSAGE_TIMER_CLEARED_STATUS = 0x043, + CEC_MESSAGE_USER_CONTROL_PRESSED = 0x44, + CEC_MESSAGE_USER_CONTROL_RELEASED = 0x45, + CEC_MESSAGE_GIVE_OSD_NAME = 0x46, + CEC_MESSAGE_SET_OSD_NAME = 0x47, + CEC_MESSAGE_SET_OSD_STRING = 0x64, + CEC_MESSAGE_SET_TIMER_PROGRAM_TITLE = 0x67, + CEC_MESSAGE_SYSTEM_AUDIO_MODE_REQUEST = 0x70, + CEC_MESSAGE_GIVE_AUDIO_STATUS = 0x71, + CEC_MESSAGE_SET_SYSTEM_AUDIO_MODE = 0x72, + CEC_MESSAGE_REPORT_AUDIO_STATUS = 0x7A, + CEC_MESSAGE_GIVE_SYSTEM_AUDIO_MODE_STATUS = 0x7D, + CEC_MESSAGE_SYSTEM_AUDIO_MODE_STATUS = 0x7E, + CEC_MESSAGE_ROUTING_CHANGE = 0x80, + CEC_MESSAGE_ROUTING_INFORMATION = 0x81, + CEC_MESSAGE_ACTIVE_SOURCE = 0x82, + CEC_MESSAGE_GIVE_PHYSICAL_ADDRESS = 0x83, + CEC_MESSAGE_REPORT_PHYSICAL_ADDRESS = 0x84, + CEC_MESSAGE_REQUEST_ACTIVE_SOURCE = 0x85, + CEC_MESSAGE_SET_STREAM_PATH = 0x86, + CEC_MESSAGE_DEVICE_VENDOR_ID = 0x87, + CEC_MESSAGE_VENDOR_COMMAND = 0x89, + CEC_MESSAGE_VENDOR_REMOTE_BUTTON_DOWN = 0x8A, + CEC_MESSAGE_VENDOR_REMOTE_BUTTON_UP = 0x8B, + CEC_MESSAGE_GIVE_DEVICE_VENDOR_ID = 0x8C, + CEC_MESSAGE_MENU_REQUEST = 0x8D, + CEC_MESSAGE_MENU_STATUS = 0x8E, + CEC_MESSAGE_GIVE_DEVICE_POWER_STATUS = 0x8F, + CEC_MESSAGE_REPORT_POWER_STATUS = 0x90, + CEC_MESSAGE_GET_MENU_LANGUAGE = 0x91, + CEC_MESSAGE_SELECT_ANALOG_SERVICE = 0x92, + CEC_MESSAGE_SELECT_DIGITAL_SERVICE = 0x93, + CEC_MESSAGE_SET_DIGITAL_TIMER = 0x97, + CEC_MESSAGE_CLEAR_DIGITAL_TIMER = 0x99, + CEC_MESSAGE_SET_AUDIO_RATE = 0x9A, + CEC_MESSAGE_INACTIVE_SOURCE = 0x9D, + CEC_MESSAGE_CEC_VERSION = 0x9E, + CEC_MESSAGE_GET_CEC_VERSION = 0x9F, + CEC_MESSAGE_VENDOR_COMMAND_WITH_ID = 0xA0, + CEC_MESSAGE_CLEAR_EXTERNAL_TIMER = 0xA1, + CEC_MESSAGE_SET_EXTERNAL_TIMER = 0xA2, + CEC_MESSAGE_INITIATE_ARC = 0xC0, + CEC_MESSAGE_REPORT_ARC_INITIATED = 0xC1, + CEC_MESSAGE_REPORT_ARC_TERMINATED = 0xC2, + CEC_MESSAGE_REQUEST_ARC_INITIATION = 0xC3, + CEC_MESSAGE_REQUEST_ARC_TERMINATION = 0xC4, + CEC_MESSAGE_TERMINATE_ARC = 0xC5, + CEC_MESSAGE_ABORT = 0xFF +}; + +/* + * Operand description [Abort Reason] + */ +enum abort_reason { + ABORT_UNRECOGNIZED_MODE = 0, + ABORT_NOT_IN_CORRECT_MODE = 1, + ABORT_CANNOT_PROVIDE_SOURCE = 2, + ABORT_INVALID_OPERAND = 3, + ABORT_REFUSED = 4, + ABORT_UNABLE_TO_DETERMINE = 5 +}; + +/* + * HDMI event type. used for hdmi_event_t. + */ +enum { + HDMI_EVENT_CEC_MESSAGE = 1, + HDMI_EVENT_HOT_PLUG = 2, +}; + +/* + * HDMI hotplug event type. Used when the event + * type is HDMI_EVENT_HOT_PLUG. + */ +enum { + HDMI_NOT_CONNECTED = 0, + HDMI_CONNECTED = 1 +}; + +/* + * error code used for send_message. + */ +enum { + HDMI_RESULT_SUCCESS = 0, + HDMI_RESULT_NACK = 1, /* not acknowledged */ + HDMI_RESULT_BUSY = 2, /* bus is busy */ + HDMI_RESULT_FAIL = 3, +}; + +/* + * HDMI port type. + */ +typedef enum hdmi_port_type { + HDMI_INPUT = 0, + HDMI_OUTPUT = 1 +} hdmi_port_type_t; + +/* + * Flags used for set_option() + */ +enum { + /* When set to false, HAL does not wake up the system upon receiving + * or . Used when user changes the TV + * settings to disable the auto TV on functionality. + * True by default. + */ + HDMI_OPTION_WAKEUP = 1, + + /* When set to false, all the CEC commands are discarded. Used when + * user changes the TV settings to disable CEC functionality. + * True by default. + */ + HDMI_OPTION_ENABLE_CEC = 2, + + /* Setting this flag to false means Android system will stop handling + * CEC service and yield the control over to the microprocessor that is + * powered on through the standby mode. When set to true, the system + * will gain the control over, hence telling the microprocessor to stop + * handling the cec commands. This is called when system goes + * in and out of standby mode to notify the microprocessor that it should + * start/stop handling CEC commands on behalf of the system. + * False by default. + */ + HDMI_OPTION_SYSTEM_CEC_CONTROL = 3, + + /* Option 4 not used */ + + /* Passes the updated language information of Android system. + * Contains 3-byte ASCII code as defined in ISO/FDIS 639-2. Can be + * used for HAL to respond to while in standby mode. + * English(eng), for example, is converted to 0x656e67. + */ + HDMI_OPTION_SET_LANG = 5, +}; + +/* + * Maximum length in bytes of cec message body (exclude header block), + * should not exceed 16 (spec CEC 6 Frame Description) + */ +#define CEC_MESSAGE_BODY_MAX_LENGTH 16 + +typedef struct cec_message { + /* logical address of sender */ + cec_logical_address_t initiator; + + /* logical address of receiver */ + cec_logical_address_t destination; + + /* Length in bytes of body, range [0, CEC_MESSAGE_BODY_MAX_LENGTH] */ + size_t length; + unsigned char body[CEC_MESSAGE_BODY_MAX_LENGTH]; +} cec_message_t; + +typedef struct hotplug_event { + /* + * true if the cable is connected; otherwise false. + */ + int connected; + int port_id; +} hotplug_event_t; + +typedef struct tx_status_event { + int status; + int opcode; /* CEC opcode */ +} tx_status_event_t; + +/* + * HDMI event generated from HAL. + */ +typedef struct hdmi_event { + int type; + struct hdmi_cec_device* dev; + union { + cec_message_t cec; + hotplug_event_t hotplug; + }; +} hdmi_event_t; + +/* + * HDMI port descriptor + */ +typedef struct hdmi_port_info { + hdmi_port_type_t type; + // Port ID should start from 1 which corresponds to HDMI "port 1". + int port_id; + int cec_supported; + int arc_supported; + uint16_t physical_address; +} hdmi_port_info_t; + +/* + * Callback function type that will be called by HAL implementation. + * Services can not close/open the device in the callback. + */ +typedef void (*event_callback_t)(const hdmi_event_t* event, void* arg); + +typedef struct hdmi_cec_module { + /** + * Common methods of the HDMI CEC module. This *must* be the first member of + * hdmi_cec_module as users of this structure will cast a hw_module_t to hdmi_cec_module + * pointer in contexts where it's known the hw_module_t references a hdmi_cec_module. + */ + struct hw_module_t common; +} hdmi_module_t; + +/* + * HDMI-CEC HAL interface definition. + */ +typedef struct hdmi_cec_device { + /** + * Common methods of the HDMI CEC device. This *must* be the first member of + * hdmi_cec_device as users of this structure will cast a hw_device_t to hdmi_cec_device + * pointer in contexts where it's known the hw_device_t references a hdmi_cec_device. + */ + struct hw_device_t common; + + /* + * (*add_logical_address)() passes the logical address that will be used + * in this system. + * + * HAL may use it to configure the hardware so that the CEC commands addressed + * the given logical address can be filtered in. This method can be called + * as many times as necessary in order to support multiple logical devices. + * addr should be in the range of valid logical addresses for the call + * to succeed. + * + * Returns 0 on success or -errno on error. + */ + int (*add_logical_address)(const struct hdmi_cec_device* dev, cec_logical_address_t addr); + + /* + * (*clear_logical_address)() tells HAL to reset all the logical addresses. + * + * It is used when the system doesn't need to process CEC command any more, + * hence to tell HAL to stop receiving commands from the CEC bus, and change + * the state back to the beginning. + */ + void (*clear_logical_address)(const struct hdmi_cec_device* dev); + + /* + * (*get_physical_address)() returns the CEC physical address. The + * address is written to addr. + * + * The physical address depends on the topology of the network formed + * by connected HDMI devices. It is therefore likely to change if the cable + * is plugged off and on again. It is advised to call get_physical_address + * to get the updated address when hot plug event takes place. + * + * Returns 0 on success or -errno on error. + */ + int (*get_physical_address)(const struct hdmi_cec_device* dev, uint16_t* addr); + + /* + * (*send_message)() transmits HDMI-CEC message to other HDMI device. + * + * The method should be designed to return in a certain amount of time not + * hanging forever, which can happen if CEC signal line is pulled low for + * some reason. HAL implementation should take the situation into account + * so as not to wait forever for the message to get sent out. + * + * It should try retransmission at least once as specified in the standard. + * + * Returns error code. See HDMI_RESULT_SUCCESS, HDMI_RESULT_NACK, and + * HDMI_RESULT_BUSY. + */ + int (*send_message)(const struct hdmi_cec_device* dev, const cec_message_t*); + + /* + * (*register_event_callback)() registers a callback that HDMI-CEC HAL + * can later use for incoming CEC messages or internal HDMI events. + * When calling from C++, use the argument arg to pass the calling object. + * It will be passed back when the callback is invoked so that the context + * can be retrieved. + */ + void (*register_event_callback)(const struct hdmi_cec_device* dev, + event_callback_t callback, void* arg); + + /* + * (*get_version)() returns the CEC version supported by underlying hardware. + */ + void (*get_version)(const struct hdmi_cec_device* dev, int* version); + + /* + * (*get_vendor_id)() returns the identifier of the vendor. It is + * the 24-bit unique company ID obtained from the IEEE Registration + * Authority Committee (RAC). + */ + void (*get_vendor_id)(const struct hdmi_cec_device* dev, uint32_t* vendor_id); + + /* + * (*get_port_info)() returns the hdmi port information of underlying hardware. + * info is the list of HDMI port information, and 'total' is the number of + * HDMI ports in the system. + */ + void (*get_port_info)(const struct hdmi_cec_device* dev, + struct hdmi_port_info* list[], int* total); + + /* + * (*set_option)() passes flags controlling the way HDMI-CEC service works down + * to HAL implementation. Those flags will be used in case the feature needs + * update in HAL itself, firmware or microcontroller. + */ + void (*set_option)(const struct hdmi_cec_device* dev, int flag, int value); + + /* + * (*set_audio_return_channel)() configures ARC circuit in the hardware logic + * to start or stop the feature. Flag can be either 1 to start the feature + * or 0 to stop it. + * + * Returns 0 on success or -errno on error. + */ + void (*set_audio_return_channel)(const struct hdmi_cec_device* dev, int port_id, int flag); + + /* + * (*is_connected)() returns the connection status of the specified port. + * Returns HDMI_CONNECTED if a device is connected, otherwise HDMI_NOT_CONNECTED. + * The HAL should watch for +5V power signal to determine the status. + */ + int (*is_connected)(const struct hdmi_cec_device* dev, int port_id); + + /* Reserved for future use to maximum 16 functions. Must be NULL. */ + void* reserved[16 - 11]; +} hdmi_cec_device_t; + +/** convenience API for opening and closing a device */ + +static inline int hdmi_cec_open(const struct hw_module_t* module, + struct hdmi_cec_device** device) { + return module->methods->open(module, + HDMI_CEC_HARDWARE_INTERFACE, (struct hw_device_t**)device); +} + +static inline int hdmi_cec_close(struct hdmi_cec_device* device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_HDMI_CEC_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/hw_auth_token.h b/third_party/android_hardware_libhardware/include/hardware/hw_auth_token.h new file mode 100644 index 00000000000000..f471d1ab7dfe21 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/hw_auth_token.h @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include + +#ifndef ANDROID_HARDWARE_HW_AUTH_TOKEN_H +#define ANDROID_HARDWARE_HW_AUTH_TOKEN_H + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +const uint8_t HW_AUTH_TOKEN_VERSION = 0; + +typedef enum { + HW_AUTH_NONE = 0, + HW_AUTH_PASSWORD = 1 << 0, + HW_AUTH_FINGERPRINT = 1 << 1, + // Additional entries should be powers of 2. + HW_AUTH_ANY = UINT32_MAX, +} hw_authenticator_type_t; + +/** + * Data format for an authentication record used to prove successful authentication. + */ +typedef struct __attribute__((__packed__)) { + uint8_t version; // Current version is 0 + uint64_t challenge; + uint64_t user_id; // secure user ID, not Android user ID + uint64_t authenticator_id; // secure authenticator ID + uint32_t authenticator_type; // hw_authenticator_type_t, in network order + uint64_t timestamp; // in network order + uint8_t hmac[32]; +} hw_auth_token_t; + +#ifdef __cplusplus +} // extern "C" +#endif // __cplusplus + +#endif // ANDROID_HARDWARE_HW_AUTH_TOKEN_H diff --git a/third_party/android_hardware_libhardware/include/hardware/hwcomposer.h b/third_party/android_hardware_libhardware/include/hardware/hwcomposer.h new file mode 100644 index 00000000000000..aa466b300a0b14 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/hwcomposer.h @@ -0,0 +1,833 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_H +#define ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_H + +#include +#include + +#include +#include +#include + +#include + +__BEGIN_DECLS + +/*****************************************************************************/ + +/* for compatibility */ +#define HWC_MODULE_API_VERSION HWC_MODULE_API_VERSION_0_1 +#define HWC_DEVICE_API_VERSION HWC_DEVICE_API_VERSION_0_1 +#define HWC_API_VERSION HWC_DEVICE_API_VERSION + +/*****************************************************************************/ + +/** + * The id of this module + */ +#define HWC_HARDWARE_MODULE_ID "hwcomposer" + +/** + * Name of the sensors device to open + */ +#define HWC_HARDWARE_COMPOSER "composer" + +typedef struct hwc_rect { + int left; + int top; + int right; + int bottom; +} hwc_rect_t; + +typedef struct hwc_frect { + float left; + float top; + float right; + float bottom; +} hwc_frect_t; + +typedef struct hwc_region { + size_t numRects; + hwc_rect_t const* rects; +} hwc_region_t; + +typedef struct hwc_color { + uint8_t r; + uint8_t g; + uint8_t b; + uint8_t a; +} hwc_color_t; + +typedef struct hwc_layer_1 { + /* + * compositionType is used to specify this layer's type and is set by either + * the hardware composer implementation, or by the caller (see below). + * + * This field is always reset to HWC_BACKGROUND or HWC_FRAMEBUFFER + * before (*prepare)() is called when the HWC_GEOMETRY_CHANGED flag is + * also set, otherwise, this field is preserved between (*prepare)() + * calls. + * + * HWC_BACKGROUND + * Always set by the caller before calling (*prepare)(), this value + * indicates this is a special "background" layer. The only valid field + * is backgroundColor. + * The HWC can toggle this value to HWC_FRAMEBUFFER to indicate it CANNOT + * handle the background color. + * + * + * HWC_FRAMEBUFFER_TARGET + * Always set by the caller before calling (*prepare)(), this value + * indicates this layer is the framebuffer surface used as the target of + * OpenGL ES composition. If the HWC sets all other layers to HWC_OVERLAY + * or HWC_BACKGROUND, then no OpenGL ES composition will be done, and + * this layer should be ignored during set(). + * + * This flag (and the framebuffer surface layer) will only be used if the + * HWC version is HWC_DEVICE_API_VERSION_1_1 or higher. In older versions, + * the OpenGL ES target surface is communicated by the (dpy, sur) fields + * in hwc_compositor_device_1_t. + * + * This value cannot be set by the HWC implementation. + * + * + * HWC_FRAMEBUFFER + * Set by the caller before calling (*prepare)() ONLY when the + * HWC_GEOMETRY_CHANGED flag is also set. + * + * Set by the HWC implementation during (*prepare)(), this indicates + * that the layer will be drawn into the framebuffer using OpenGL ES. + * The HWC can toggle this value to HWC_OVERLAY to indicate it will + * handle the layer. + * + * + * HWC_OVERLAY + * Set by the HWC implementation during (*prepare)(), this indicates + * that the layer will be handled by the HWC (ie: it must not be + * composited with OpenGL ES). + * + * + * HWC_SIDEBAND + * Set by the caller before calling (*prepare)(), this value indicates + * the contents of this layer come from a sideband video stream. + * + * The h/w composer is responsible for receiving new image buffers from + * the stream at the appropriate time (e.g. synchronized to a separate + * audio stream), compositing them with the current contents of other + * layers, and displaying the resulting image. This happens + * independently of the normal prepare/set cycle. The prepare/set calls + * only happen when other layers change, or when properties of the + * sideband layer such as position or size change. + * + * If the h/w composer can't handle the layer as a sideband stream for + * some reason (e.g. unsupported scaling/blending/rotation, or too many + * sideband layers) it can set compositionType to HWC_FRAMEBUFFER in + * (*prepare)(). However, doing so will result in the layer being shown + * as a solid color since the platform is not currently able to composite + * sideband layers with the GPU. This may be improved in future + * versions of the platform. + * + * + * HWC_CURSOR_OVERLAY + * Set by the HWC implementation during (*prepare)(), this value + * indicates the layer's composition will now be handled by the HWC. + * Additionally, the client can now asynchronously update the on-screen + * position of this layer using the setCursorPositionAsync() api. + */ + int32_t compositionType; + + /* + * hints is bit mask set by the HWC implementation during (*prepare)(). + * It is preserved between (*prepare)() calls, unless the + * HWC_GEOMETRY_CHANGED flag is set, in which case it is reset to 0. + * + * see hwc_layer_t::hints + */ + uint32_t hints; + + /* see hwc_layer_t::flags */ + uint32_t flags; + + union { + /* color of the background. hwc_color_t.a is ignored */ + hwc_color_t backgroundColor; + + struct { + union { + /* When compositionType is HWC_FRAMEBUFFER, HWC_OVERLAY, + * HWC_FRAMEBUFFER_TARGET, this is the handle of the buffer to + * compose. This handle is guaranteed to have been allocated + * from gralloc using the GRALLOC_USAGE_HW_COMPOSER usage flag. + * If the layer's handle is unchanged across two consecutive + * prepare calls and the HWC_GEOMETRY_CHANGED flag is not set + * for the second call then the HWComposer implementation may + * assume that the contents of the buffer have not changed. */ + buffer_handle_t handle; + + /* When compositionType is HWC_SIDEBAND, this is the handle + * of the sideband video stream to compose. */ + const native_handle_t* sidebandStream; + }; + + /* transformation to apply to the buffer during composition */ + uint32_t transform; + + /* blending to apply during composition */ + int32_t blending; + + /* area of the source to consider, the origin is the top-left corner of + * the buffer. As of HWC_DEVICE_API_VERSION_1_3, sourceRect uses floats. + * If the h/w can't support a non-integer source crop rectangle, it should + * punt to OpenGL ES composition. + */ + union { + // crop rectangle in integer (pre HWC_DEVICE_API_VERSION_1_3) + hwc_rect_t sourceCropi; + hwc_rect_t sourceCrop; // just for source compatibility + // crop rectangle in floats (as of HWC_DEVICE_API_VERSION_1_3) + hwc_frect_t sourceCropf; + }; + + /* where to composite the sourceCrop onto the display. The sourceCrop + * is scaled using linear filtering to the displayFrame. The origin is the + * top-left corner of the screen. + */ + hwc_rect_t displayFrame; + + /* visible region in screen space. The origin is the + * top-left corner of the screen. + * The visible region INCLUDES areas overlapped by a translucent layer. + */ + hwc_region_t visibleRegionScreen; + + /* Sync fence object that will be signaled when the buffer's + * contents are available. May be -1 if the contents are already + * available. This field is only valid during set(), and should be + * ignored during prepare(). The set() call must not wait for the + * fence to be signaled before returning, but the HWC must wait for + * all buffers to be signaled before reading from them. + * + * HWC_FRAMEBUFFER layers will never have an acquire fence, since + * reads from them are complete before the framebuffer is ready for + * display. + * + * HWC_SIDEBAND layers will never have an acquire fence, since + * synchronization is handled through implementation-defined + * sideband mechanisms. + * + * The HWC takes ownership of the acquireFenceFd and is responsible + * for closing it when no longer needed. + */ + int acquireFenceFd; + + /* During set() the HWC must set this field to a file descriptor for + * a sync fence object that will signal after the HWC has finished + * reading from the buffer. The field is ignored by prepare(). Each + * layer should have a unique file descriptor, even if more than one + * refer to the same underlying fence object; this allows each to be + * closed independently. + * + * If buffer reads can complete at significantly different times, + * then using independent fences is preferred. For example, if the + * HWC handles some layers with a blit engine and others with + * overlays, then the blit layers can be reused immediately after + * the blit completes, but the overlay layers can't be reused until + * a subsequent frame has been displayed. + * + * Since HWC doesn't read from HWC_FRAMEBUFFER layers, it shouldn't + * produce a release fence for them. The releaseFenceFd will be -1 + * for these layers when set() is called. + * + * Since HWC_SIDEBAND buffers don't pass through the HWC client, + * the HWC shouldn't produce a release fence for them. The + * releaseFenceFd will be -1 for these layers when set() is called. + * + * The HWC client taks ownership of the releaseFenceFd and is + * responsible for closing it when no longer needed. + */ + int releaseFenceFd; + + /* + * Availability: HWC_DEVICE_API_VERSION_1_2 + * + * Alpha value applied to the whole layer. The effective + * value of each pixel is computed as: + * + * if (blending == HWC_BLENDING_PREMULT) + * pixel.rgb = pixel.rgb * planeAlpha / 255 + * pixel.a = pixel.a * planeAlpha / 255 + * + * Then blending proceeds as usual according to the "blending" + * field above. + * + * NOTE: planeAlpha applies to YUV layers as well: + * + * pixel.rgb = yuv_to_rgb(pixel.yuv) + * if (blending == HWC_BLENDING_PREMULT) + * pixel.rgb = pixel.rgb * planeAlpha / 255 + * pixel.a = planeAlpha + * + * + * IMPLEMENTATION NOTE: + * + * If the source image doesn't have an alpha channel, then + * the h/w can use the HWC_BLENDING_COVERAGE equations instead of + * HWC_BLENDING_PREMULT and simply set the alpha channel to + * planeAlpha. + * + * e.g.: + * + * if (blending == HWC_BLENDING_PREMULT) + * blending = HWC_BLENDING_COVERAGE; + * pixel.a = planeAlpha; + * + */ + uint8_t planeAlpha; + + /* Pad to 32 bits */ + uint8_t _pad[3]; + + /* + * Availability: HWC_DEVICE_API_VERSION_1_5 + * + * This defines the region of the source buffer that has been + * modified since the last frame. + * + * If surfaceDamage.numRects > 0, then it may be assumed that any + * portion of the source buffer not covered by one of the rects has + * not been modified this frame. If surfaceDamage.numRects == 0, + * then the whole source buffer must be treated as if it had been + * modified. + * + * If the layer's contents are not modified relative to the prior + * prepare/set cycle, surfaceDamage will contain exactly one empty + * rect ([0, 0, 0, 0]). + * + * The damage rects are relative to the pre-transformed buffer, and + * their origin is the top-left corner. + */ + hwc_region_t surfaceDamage; + }; + }; + +#ifdef __LP64__ + /* + * For 64-bit mode, this struct is 120 bytes (and 8-byte aligned), and needs + * to be padded as such to maintain binary compatibility. + */ + uint8_t reserved[120 - 112]; +#else + /* + * For 32-bit mode, this struct is 96 bytes, and needs to be padded as such + * to maintain binary compatibility. + */ + uint8_t reserved[96 - 84]; +#endif + +} hwc_layer_1_t; + +/* This represents a display, typically an EGLDisplay object */ +typedef void* hwc_display_t; + +/* This represents a surface, typically an EGLSurface object */ +typedef void* hwc_surface_t; + +/* + * hwc_display_contents_1_t::flags values + */ +enum { + /* + * HWC_GEOMETRY_CHANGED is set by SurfaceFlinger to indicate that the list + * passed to (*prepare)() has changed by more than just the buffer handles + * and acquire fences. + */ + HWC_GEOMETRY_CHANGED = 0x00000001, +}; + +/* + * Description of the contents to output on a display. + * + * This is the top-level structure passed to the prepare and set calls to + * negotiate and commit the composition of a display image. + */ +typedef struct hwc_display_contents_1 { + /* File descriptor referring to a Sync HAL fence object which will signal + * when this composition is retired. For a physical display, a composition + * is retired when it has been replaced on-screen by a subsequent set. For + * a virtual display, the composition is retired when the writes to + * outputBuffer are complete and can be read. The fence object is created + * and returned by the set call; this field will be -1 on entry to prepare + * and set. SurfaceFlinger will close the returned file descriptor. + */ + int retireFenceFd; + + union { + /* Fields only relevant for HWC_DEVICE_VERSION_1_0. */ + struct { + /* (dpy, sur) is the target of SurfaceFlinger's OpenGL ES + * composition for HWC_DEVICE_VERSION_1_0. They aren't relevant to + * prepare. The set call should commit this surface atomically to + * the display along with any overlay layers. + */ + hwc_display_t dpy; + hwc_surface_t sur; + }; + + /* These fields are used for virtual displays when the h/w composer + * version is at least HWC_DEVICE_VERSION_1_3. */ + struct { + /* outbuf is the buffer that receives the composed image for + * virtual displays. Writes to the outbuf must wait until + * outbufAcquireFenceFd signals. A fence that will signal when + * writes to outbuf are complete should be returned in + * retireFenceFd. + * + * This field is set before prepare(), so properties of the buffer + * can be used to decide which layers can be handled by h/w + * composer. + * + * If prepare() sets all layers to FRAMEBUFFER, then GLES + * composition will happen directly to the output buffer. In this + * case, both outbuf and the FRAMEBUFFER_TARGET layer's buffer will + * be the same, and set() has no work to do besides managing fences. + * + * If the TARGET_FORCE_HWC_FOR_VIRTUAL_DISPLAYS board config + * variable is defined (not the default), then this behavior is + * changed: if all layers are marked for FRAMEBUFFER, GLES + * composition will take place to a scratch framebuffer, and + * h/w composer must copy it to the output buffer. This allows the + * h/w composer to do format conversion if there are cases where + * that is more desirable than doing it in the GLES driver or at the + * virtual display consumer. + * + * If some or all layers are marked OVERLAY, then the framebuffer + * and output buffer will be different. As with physical displays, + * the framebuffer handle will not change between frames if all + * layers are marked for OVERLAY. + */ + buffer_handle_t outbuf; + + /* File descriptor for a fence that will signal when outbuf is + * ready to be written. The h/w composer is responsible for closing + * this when no longer needed. + * + * Will be -1 whenever outbuf is NULL, or when the outbuf can be + * written immediately. + */ + int outbufAcquireFenceFd; + }; + }; + + /* List of layers that will be composed on the display. The buffer handles + * in the list will be unique. If numHwLayers is 0, all composition will be + * performed by SurfaceFlinger. + */ + uint32_t flags; + size_t numHwLayers; + hwc_layer_1_t hwLayers[0]; + +} hwc_display_contents_1_t; + +/* see hwc_composer_device::registerProcs() + * All of the callbacks are required and non-NULL unless otherwise noted. + */ +typedef struct hwc_procs { + /* + * (*invalidate)() triggers a screen refresh, in particular prepare and set + * will be called shortly after this call is made. Note that there is + * NO GUARANTEE that the screen refresh will happen after invalidate() + * returns (in particular, it could happen before). + * invalidate() is GUARANTEED TO NOT CALL BACK into the h/w composer HAL and + * it is safe to call invalidate() from any of hwc_composer_device + * hooks, unless noted otherwise. + */ + void (*invalidate)(const struct hwc_procs* procs); + + /* + * (*vsync)() is called by the h/w composer HAL when a vsync event is + * received and HWC_EVENT_VSYNC is enabled on a display + * (see: hwc_event_control). + * + * the "disp" parameter indicates which display the vsync event is for. + * the "timestamp" parameter is the system monotonic clock timestamp in + * nanosecond of when the vsync event happened. + * + * vsync() is GUARANTEED TO NOT CALL BACK into the h/w composer HAL. + * + * It is expected that vsync() is called from a thread of at least + * HAL_PRIORITY_URGENT_DISPLAY with as little latency as possible, + * typically less than 0.5 ms. + * + * It is a (silent) error to have HWC_EVENT_VSYNC enabled when calling + * hwc_composer_device.set(..., 0, 0, 0) (screen off). The implementation + * can either stop or continue to process VSYNC events, but must not + * crash or cause other problems. + */ + void (*vsync)(const struct hwc_procs* procs, int disp, int64_t timestamp); + + /* + * (*hotplug)() is called by the h/w composer HAL when a display is + * connected or disconnected. The PRIMARY display is always connected and + * the hotplug callback should not be called for it. + * + * The disp parameter indicates which display type this event is for. + * The connected parameter indicates whether the display has just been + * connected (1) or disconnected (0). + * + * The hotplug() callback may call back into the h/w composer on the same + * thread to query refresh rate and dpi for the display. Additionally, + * other threads may be calling into the h/w composer while the callback + * is in progress. + * + * The h/w composer must serialize calls to the hotplug callback; only + * one thread may call it at a time. + * + * This callback will be NULL if the h/w composer is using + * HWC_DEVICE_API_VERSION_1_0. + */ + void (*hotplug)(const struct hwc_procs* procs, int disp, int connected); + +} hwc_procs_t; + + +/*****************************************************************************/ + +typedef struct hwc_module { + /** + * Common methods of the hardware composer module. This *must* be the first member of + * hwc_module as users of this structure will cast a hw_module_t to + * hwc_module pointer in contexts where it's known the hw_module_t references a + * hwc_module. + */ + struct hw_module_t common; +} hwc_module_t; + +typedef struct hwc_composer_device_1 { + /** + * Common methods of the hardware composer device. This *must* be the first member of + * hwc_composer_device_1 as users of this structure will cast a hw_device_t to + * hwc_composer_device_1 pointer in contexts where it's known the hw_device_t references a + * hwc_composer_device_1. + */ + struct hw_device_t common; + + /* + * (*prepare)() is called for each frame before composition and is used by + * SurfaceFlinger to determine what composition steps the HWC can handle. + * + * (*prepare)() can be called more than once, the last call prevails. + * + * The HWC responds by setting the compositionType field in each layer to + * either HWC_FRAMEBUFFER, HWC_OVERLAY, or HWC_CURSOR_OVERLAY. For the + * HWC_FRAMEBUFFER type, composition for the layer is handled by + * SurfaceFlinger with OpenGL ES. For the latter two overlay types, + * the HWC will have to handle the layer's composition. compositionType + * and hints are preserved between (*prepare)() calles unless the + * HWC_GEOMETRY_CHANGED flag is set. + * + * (*prepare)() is called with HWC_GEOMETRY_CHANGED to indicate that the + * list's geometry has changed, that is, when more than just the buffer's + * handles have been updated. Typically this happens (but is not limited to) + * when a window is added, removed, resized or moved. In this case + * compositionType and hints are reset to their default value. + * + * For HWC 1.0, numDisplays will always be one, and displays[0] will be + * non-NULL. + * + * For HWC 1.1, numDisplays will always be HWC_NUM_PHYSICAL_DISPLAY_TYPES. + * Entries for unsupported or disabled/disconnected display types will be + * NULL. + * + * In HWC 1.3, numDisplays may be up to HWC_NUM_DISPLAY_TYPES. The extra + * entries correspond to enabled virtual displays, and will be non-NULL. + * + * returns: 0 on success. An negative error code on error. If an error is + * returned, SurfaceFlinger will assume that none of the layer will be + * handled by the HWC. + */ + int (*prepare)(struct hwc_composer_device_1 *dev, + size_t numDisplays, hwc_display_contents_1_t** displays); + + /* + * (*set)() is used in place of eglSwapBuffers(), and assumes the same + * functionality, except it also commits the work list atomically with + * the actual eglSwapBuffers(). + * + * The layer lists are guaranteed to be the same as the ones returned from + * the last call to (*prepare)(). + * + * When this call returns the caller assumes that the displays will be + * updated in the near future with the content of their work lists, without + * artifacts during the transition from the previous frame. + * + * A display with zero layers indicates that the entire composition has + * been handled by SurfaceFlinger with OpenGL ES. In this case, (*set)() + * behaves just like eglSwapBuffers(). + * + * For HWC 1.0, numDisplays will always be one, and displays[0] will be + * non-NULL. + * + * For HWC 1.1, numDisplays will always be HWC_NUM_PHYSICAL_DISPLAY_TYPES. + * Entries for unsupported or disabled/disconnected display types will be + * NULL. + * + * In HWC 1.3, numDisplays may be up to HWC_NUM_DISPLAY_TYPES. The extra + * entries correspond to enabled virtual displays, and will be non-NULL. + * + * IMPORTANT NOTE: There is an implicit layer containing opaque black + * pixels behind all the layers in the list. It is the responsibility of + * the hwcomposer module to make sure black pixels are output (or blended + * from). + * + * IMPORTANT NOTE: In the event of an error this call *MUST* still cause + * any fences returned in the previous call to set to eventually become + * signaled. The caller may have already issued wait commands on these + * fences, and having set return without causing those fences to signal + * will likely result in a deadlock. + * + * returns: 0 on success. A negative error code on error: + * HWC_EGL_ERROR: eglGetError() will provide the proper error code (only + * allowed prior to HWComposer 1.1) + * Another code for non EGL errors. + */ + int (*set)(struct hwc_composer_device_1 *dev, + size_t numDisplays, hwc_display_contents_1_t** displays); + + /* + * eventControl(..., event, enabled) + * Enables or disables h/w composer events for a display. + * + * eventControl can be called from any thread and takes effect + * immediately. + * + * Supported events are: + * HWC_EVENT_VSYNC + * + * returns -EINVAL if the "event" parameter is not one of the value above + * or if the "enabled" parameter is not 0 or 1. + */ + int (*eventControl)(struct hwc_composer_device_1* dev, int disp, + int event, int enabled); + + union { + /* + * For HWC 1.3 and earlier, the blank() interface is used. + * + * blank(..., blank) + * Blanks or unblanks a display's screen. + * + * Turns the screen off when blank is nonzero, on when blank is zero. + * Multiple sequential calls with the same blank value must be + * supported. + * The screen state transition must be be complete when the function + * returns. + * + * returns 0 on success, negative on error. + */ + int (*blank)(struct hwc_composer_device_1* dev, int disp, int blank); + + /* + * For HWC 1.4 and above, setPowerMode() will be used in place of + * blank(). + * + * setPowerMode(..., mode) + * Sets the display screen's power state. + * + * Refer to the documentation of the HWC_POWER_MODE_* constants + * for information about each power mode. + * + * The functionality is similar to the blank() command in previous + * versions of HWC, but with support for more power states. + * + * The display driver is expected to retain and restore the low power + * state of the display while entering and exiting from suspend. + * + * Multiple sequential calls with the same mode value must be supported. + * + * The screen state transition must be be complete when the function + * returns. + * + * returns 0 on success, negative on error. + */ + int (*setPowerMode)(struct hwc_composer_device_1* dev, int disp, + int mode); + }; + + /* + * Used to retrieve information about the h/w composer + * + * Returns 0 on success or -errno on error. + */ + int (*query)(struct hwc_composer_device_1* dev, int what, int* value); + + /* + * (*registerProcs)() registers callbacks that the h/w composer HAL can + * later use. It will be called immediately after the composer device is + * opened with non-NULL procs. It is FORBIDDEN to call any of the callbacks + * from within registerProcs(). registerProcs() must save the hwc_procs_t + * pointer which is needed when calling a registered callback. + */ + void (*registerProcs)(struct hwc_composer_device_1* dev, + hwc_procs_t const* procs); + + /* + * This field is OPTIONAL and can be NULL. + * + * If non NULL it will be called by SurfaceFlinger on dumpsys + */ + void (*dump)(struct hwc_composer_device_1* dev, char *buff, int buff_len); + + /* + * (*getDisplayConfigs)() returns handles for the configurations available + * on the connected display. These handles must remain valid as long as the + * display is connected. + * + * Configuration handles are written to configs. The number of entries + * allocated by the caller is passed in *numConfigs; getDisplayConfigs must + * not try to write more than this number of config handles. On return, the + * total number of configurations available for the display is returned in + * *numConfigs. If *numConfigs is zero on entry, then configs may be NULL. + * + * Hardware composers implementing HWC_DEVICE_API_VERSION_1_3 or prior + * shall choose one configuration to activate and report it as the first + * entry in the returned list. Reporting the inactive configurations is not + * required. + * + * HWC_DEVICE_API_VERSION_1_4 and later provide configuration management + * through SurfaceFlinger, and hardware composers implementing these APIs + * must also provide getActiveConfig and setActiveConfig. Hardware composers + * implementing these API versions may choose not to activate any + * configuration, leaving configuration selection to higher levels of the + * framework. + * + * Returns 0 on success or a negative error code on error. If disp is a + * hotpluggable display type and no display is connected, an error shall be + * returned. + * + * This field is REQUIRED for HWC_DEVICE_API_VERSION_1_1 and later. + * It shall be NULL for previous versions. + */ + int (*getDisplayConfigs)(struct hwc_composer_device_1* dev, int disp, + uint32_t* configs, size_t* numConfigs); + + /* + * (*getDisplayAttributes)() returns attributes for a specific config of a + * connected display. The config parameter is one of the config handles + * returned by getDisplayConfigs. + * + * The list of attributes to return is provided in the attributes + * parameter, terminated by HWC_DISPLAY_NO_ATTRIBUTE. The value for each + * requested attribute is written in order to the values array. The + * HWC_DISPLAY_NO_ATTRIBUTE attribute does not have a value, so the values + * array will have one less value than the attributes array. + * + * This field is REQUIRED for HWC_DEVICE_API_VERSION_1_1 and later. + * It shall be NULL for previous versions. + * + * If disp is a hotpluggable display type and no display is connected, + * or if config is not a valid configuration for the display, a negative + * error code shall be returned. + */ + int (*getDisplayAttributes)(struct hwc_composer_device_1* dev, int disp, + uint32_t config, const uint32_t* attributes, int32_t* values); + + /* + * (*getActiveConfig)() returns the index of the configuration that is + * currently active on the connected display. The index is relative to + * the list of configuration handles returned by getDisplayConfigs. If there + * is no active configuration, -1 shall be returned. + * + * Returns the configuration index on success or -1 on error. + * + * This field is REQUIRED for HWC_DEVICE_API_VERSION_1_4 and later. + * It shall be NULL for previous versions. + */ + int (*getActiveConfig)(struct hwc_composer_device_1* dev, int disp); + + /* + * (*setActiveConfig)() instructs the hardware composer to switch to the + * display configuration at the given index in the list of configuration + * handles returned by getDisplayConfigs. + * + * If this function returns without error, any subsequent calls to + * getActiveConfig shall return the index set by this function until one + * of the following occurs: + * 1) Another successful call of this function + * 2) The display is disconnected + * + * Returns 0 on success or a negative error code on error. If disp is a + * hotpluggable display type and no display is connected, or if index is + * outside of the range of hardware configurations returned by + * getDisplayConfigs, an error shall be returned. + * + * This field is REQUIRED for HWC_DEVICE_API_VERSION_1_4 and later. + * It shall be NULL for previous versions. + */ + int (*setActiveConfig)(struct hwc_composer_device_1* dev, int disp, + int index); + /* + * Asynchronously update the location of the cursor layer. + * + * Within the standard prepare()/set() composition loop, the client + * (surfaceflinger) can request that a given layer uses dedicated cursor + * composition hardware by specifiying the HWC_IS_CURSOR_LAYER flag. Only + * one layer per display can have this flag set. If the layer is suitable + * for the platform's cursor hardware, hwcomposer will return from prepare() + * a composition type of HWC_CURSOR_OVERLAY for that layer. This indicates + * not only that the client is not responsible for compositing that layer, + * but also that the client can continue to update the position of that layer + * after a call to set(). This can reduce the visible latency of mouse + * movement to visible, on-screen cursor updates. Calls to + * setCursorPositionAsync() may be made from a different thread doing the + * prepare()/set() composition loop, but care must be taken to not interleave + * calls of setCursorPositionAsync() between calls of set()/prepare(). + * + * Notes: + * - Only one layer per display can be specified as a cursor layer with + * HWC_IS_CURSOR_LAYER. + * - hwcomposer will only return one layer per display as HWC_CURSOR_OVERLAY + * - This returns 0 on success or -errno on error. + * - This field is optional for HWC_DEVICE_API_VERSION_1_4 and later. It + * should be null for previous versions. + */ + int (*setCursorPositionAsync)(struct hwc_composer_device_1 *dev, int disp, int x_pos, int y_pos); + + /* + * Reserved for future use. Must be NULL. + */ + void* reserved_proc[1]; + +} hwc_composer_device_1_t; + +/** convenience API for opening and closing a device */ + +static inline int hwc_open_1(const struct hw_module_t* module, + hwc_composer_device_1_t** device) { + return module->methods->open(module, + HWC_HARDWARE_COMPOSER, (struct hw_device_t**)device); +} + +static inline int hwc_close_1(hwc_composer_device_1_t* device) { + return device->common.close(&device->common); +} + +/*****************************************************************************/ + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/hwcomposer_defs.h b/third_party/android_hardware_libhardware/include/hardware/hwcomposer_defs.h new file mode 100644 index 00000000000000..a90822a4b81288 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/hwcomposer_defs.h @@ -0,0 +1,263 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_DEFS_H +#define ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_DEFS_H + +#include +#include + +#include +#include +#include + +__BEGIN_DECLS + +/*****************************************************************************/ + +#define HWC_HEADER_VERSION 1 + +#define HWC_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) + +#define HWC_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION_2(1, 0, HWC_HEADER_VERSION) +#define HWC_DEVICE_API_VERSION_1_1 HARDWARE_DEVICE_API_VERSION_2(1, 1, HWC_HEADER_VERSION) +#define HWC_DEVICE_API_VERSION_1_2 HARDWARE_DEVICE_API_VERSION_2(1, 2, HWC_HEADER_VERSION) +#define HWC_DEVICE_API_VERSION_1_3 HARDWARE_DEVICE_API_VERSION_2(1, 3, HWC_HEADER_VERSION) +#define HWC_DEVICE_API_VERSION_1_4 HARDWARE_DEVICE_API_VERSION_2(1, 4, HWC_HEADER_VERSION) +#define HWC_DEVICE_API_VERSION_1_5 HARDWARE_DEVICE_API_VERSION_2(1, 5, HWC_HEADER_VERSION) + +enum { + /* hwc_composer_device_t::set failed in EGL */ + HWC_EGL_ERROR = -1 +}; + +/* + * hwc_layer_t::hints values + * Hints are set by the HAL and read by SurfaceFlinger + */ +enum { + /* + * HWC can set the HWC_HINT_TRIPLE_BUFFER hint to indicate to SurfaceFlinger + * that it should triple buffer this layer. Typically HWC does this when + * the layer will be unavailable for use for an extended period of time, + * e.g. if the display will be fetching data directly from the layer and + * the layer can not be modified until after the next set(). + */ + HWC_HINT_TRIPLE_BUFFER = 0x00000001, + + /* + * HWC sets HWC_HINT_CLEAR_FB to tell SurfaceFlinger that it should clear the + * framebuffer with transparent pixels where this layer would be. + * SurfaceFlinger will only honor this flag when the layer has no blending + * + */ + HWC_HINT_CLEAR_FB = 0x00000002 +}; + +/* + * hwc_layer_t::flags values + * Flags are set by SurfaceFlinger and read by the HAL + */ +enum { + /* + * HWC_SKIP_LAYER is set by SurfaceFlnger to indicate that the HAL + * shall not consider this layer for composition as it will be handled + * by SurfaceFlinger (just as if compositionType was set to HWC_OVERLAY). + */ + HWC_SKIP_LAYER = 0x00000001, + + /* + * HWC_IS_CURSOR_LAYER is set by surfaceflinger to indicate that this + * layer is being used as a cursor on this particular display, and that + * surfaceflinger can potentially perform asynchronous position updates for + * this layer. If a call to prepare() returns HWC_CURSOR_OVERLAY for the + * composition type of this layer, then the hwcomposer will allow async + * position updates to this layer via setCursorPositionAsync(). + */ + HWC_IS_CURSOR_LAYER = 0x00000002 +}; + +/* + * hwc_layer_t::compositionType values + */ +enum { + /* this layer is to be drawn into the framebuffer by SurfaceFlinger */ + HWC_FRAMEBUFFER = 0, + + /* this layer will be handled in the HWC */ + HWC_OVERLAY = 1, + + /* this is the background layer. it's used to set the background color. + * there is only a single background layer */ + HWC_BACKGROUND = 2, + + /* this layer holds the result of compositing the HWC_FRAMEBUFFER layers. + * Added in HWC_DEVICE_API_VERSION_1_1. */ + HWC_FRAMEBUFFER_TARGET = 3, + + /* this layer's contents are taken from a sideband buffer stream. + * Added in HWC_DEVICE_API_VERSION_1_4. */ + HWC_SIDEBAND = 4, + + /* this layer's composition will be handled by hwcomposer by dedicated + cursor overlay hardware. hwcomposer will also all async position updates + of this layer outside of the normal prepare()/set() loop. Added in + HWC_DEVICE_API_VERSION_1_4. */ + HWC_CURSOR_OVERLAY = 5 + }; +/* + * hwc_layer_t::blending values + */ +enum { + /* no blending */ + HWC_BLENDING_NONE = 0x0100, + + /* ONE / ONE_MINUS_SRC_ALPHA */ + HWC_BLENDING_PREMULT = 0x0105, + + /* SRC_ALPHA / ONE_MINUS_SRC_ALPHA */ + HWC_BLENDING_COVERAGE = 0x0405 +}; + +/* + * hwc_layer_t::transform values + */ +enum { + /* flip source image horizontally */ + HWC_TRANSFORM_FLIP_H = HAL_TRANSFORM_FLIP_H, + /* flip source image vertically */ + HWC_TRANSFORM_FLIP_V = HAL_TRANSFORM_FLIP_V, + /* rotate source image 90 degrees clock-wise */ + HWC_TRANSFORM_ROT_90 = HAL_TRANSFORM_ROT_90, + /* rotate source image 180 degrees */ + HWC_TRANSFORM_ROT_180 = HAL_TRANSFORM_ROT_180, + /* rotate source image 270 degrees clock-wise */ + HWC_TRANSFORM_ROT_270 = HAL_TRANSFORM_ROT_270, +}; + +/* attributes queriable with query() */ +enum { + /* + * Must return 1 if the background layer is supported, 0 otherwise. + */ + HWC_BACKGROUND_LAYER_SUPPORTED = 0, + + /* + * Returns the vsync period in nanoseconds. + * + * This query is not used for HWC_DEVICE_API_VERSION_1_1 and later. + * Instead, the per-display attribute HWC_DISPLAY_VSYNC_PERIOD is used. + */ + HWC_VSYNC_PERIOD = 1, + + /* + * Availability: HWC_DEVICE_API_VERSION_1_1 + * Returns a mask of supported display types. + */ + HWC_DISPLAY_TYPES_SUPPORTED = 2, +}; + +/* display attributes returned by getDisplayAttributes() */ +enum { + /* Indicates the end of an attribute list */ + HWC_DISPLAY_NO_ATTRIBUTE = 0, + + /* The vsync period in nanoseconds */ + HWC_DISPLAY_VSYNC_PERIOD = 1, + + /* The number of pixels in the horizontal and vertical directions. */ + HWC_DISPLAY_WIDTH = 2, + HWC_DISPLAY_HEIGHT = 3, + + /* The number of pixels per thousand inches of this configuration. + * + * Scaling DPI by 1000 allows it to be stored in an int without losing + * too much precision. + * + * If the DPI for a configuration is unavailable or the HWC implementation + * considers it unreliable, it should set these attributes to zero. + */ + HWC_DISPLAY_DPI_X = 4, + HWC_DISPLAY_DPI_Y = 5, + + /* Indicates which of the vendor-defined color transforms is provided by + * this configuration. */ + HWC_DISPLAY_COLOR_TRANSFORM = 6, +}; + +/* Allowed events for hwc_methods::eventControl() */ +enum { + HWC_EVENT_VSYNC = 0 +}; + +/* Display types and associated mask bits. */ +enum { + HWC_DISPLAY_PRIMARY = 0, + HWC_DISPLAY_EXTERNAL = 1, // HDMI, DP, etc. +#ifdef QTI_BSP + HWC_DISPLAY_TERTIARY = 2, + HWC_DISPLAY_VIRTUAL = 3, + + HWC_NUM_PHYSICAL_DISPLAY_TYPES = 3, + HWC_NUM_DISPLAY_TYPES = 4, +#else + HWC_DISPLAY_VIRTUAL = 2, + + HWC_NUM_PHYSICAL_DISPLAY_TYPES = 2, + HWC_NUM_DISPLAY_TYPES = 3, +#endif +}; + +enum { + HWC_DISPLAY_PRIMARY_BIT = 1 << HWC_DISPLAY_PRIMARY, + HWC_DISPLAY_EXTERNAL_BIT = 1 << HWC_DISPLAY_EXTERNAL, +#ifdef QTI_BSP + HWC_DISPLAY_TERTIARY_BIT = 1 << HWC_DISPLAY_TERTIARY, +#endif + HWC_DISPLAY_VIRTUAL_BIT = 1 << HWC_DISPLAY_VIRTUAL, +}; + +/* Display power modes */ +enum { + /* The display is turned off (blanked). */ + HWC_POWER_MODE_OFF = 0, + /* The display is turned on and configured in a low power state + * that is suitable for presenting ambient information to the user, + * possibly with lower fidelity than normal but greater efficiency. */ + HWC_POWER_MODE_DOZE = 1, + /* The display is turned on normally. */ + HWC_POWER_MODE_NORMAL = 2, + /* The display is configured as in HWC_POWER_MODE_DOZE but may + * stop applying frame buffer updates from the graphics subsystem. + * This power mode is effectively a hint from the doze dream to + * tell the hardware that it is done drawing to the display for the + * time being and that the display should remain on in a low power + * state and continue showing its current contents indefinitely + * until the mode changes. + * + * This mode may also be used as a signal to enable hardware-based doze + * functionality. In this case, the doze dream is effectively + * indicating that the hardware is free to take over the display + * and manage it autonomously to implement low power always-on display + * functionality. */ + HWC_POWER_MODE_DOZE_SUSPEND = 3, +}; + +/*****************************************************************************/ + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_HWCOMPOSER_DEFS_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/input.h b/third_party/android_hardware_libhardware/include/hardware/input.h new file mode 100644 index 00000000000000..969b8ce5701af7 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/input.h @@ -0,0 +1,549 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_INPUT_H +#define ANDROID_INCLUDE_HARDWARE_INPUT_H + +#include +#include + +__BEGIN_DECLS + +#define INPUT_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define INPUT_HARDWARE_MODULE_ID "input" + +#define INPUT_INSTANCE_EVDEV "evdev" + +typedef enum input_bus { + INPUT_BUS_BT, + INPUT_BUS_USB, + INPUT_BUS_SERIAL, + INPUT_BUS_BUILTIN +} input_bus_t; + +typedef struct input_host input_host_t; + +typedef struct input_device_handle input_device_handle_t; + +typedef struct input_device_identifier input_device_identifier_t; + +typedef struct input_device_definition input_device_definition_t; + +typedef struct input_report_definition input_report_definition_t; + +typedef struct input_report input_report_t; + +typedef struct input_collection input_collection_t; + +typedef struct input_property_map input_property_map_t; + +typedef struct input_property input_property_t; + +typedef enum { + // keycodes + INPUT_USAGE_KEYCODE_UNKNOWN, + INPUT_USAGE_KEYCODE_SOFT_LEFT, + INPUT_USAGE_KEYCODE_SOFT_RIGHT, + INPUT_USAGE_KEYCODE_HOME, + INPUT_USAGE_KEYCODE_BACK, + INPUT_USAGE_KEYCODE_CALL, + INPUT_USAGE_KEYCODE_ENDCALL, + INPUT_USAGE_KEYCODE_0, + INPUT_USAGE_KEYCODE_1, + INPUT_USAGE_KEYCODE_2, + INPUT_USAGE_KEYCODE_3, + INPUT_USAGE_KEYCODE_4, + INPUT_USAGE_KEYCODE_5, + INPUT_USAGE_KEYCODE_6, + INPUT_USAGE_KEYCODE_7, + INPUT_USAGE_KEYCODE_8, + INPUT_USAGE_KEYCODE_9, + INPUT_USAGE_KEYCODE_STAR, + INPUT_USAGE_KEYCODE_POUND, + INPUT_USAGE_KEYCODE_DPAD_UP, + INPUT_USAGE_KEYCODE_DPAD_DOWN, + INPUT_USAGE_KEYCODE_DPAD_LEFT, + INPUT_USAGE_KEYCODE_DPAD_RIGHT, + INPUT_USAGE_KEYCODE_DPAD_CENTER, + INPUT_USAGE_KEYCODE_VOLUME_UP, + INPUT_USAGE_KEYCODE_VOLUME_DOWN, + INPUT_USAGE_KEYCODE_POWER, + INPUT_USAGE_KEYCODE_CAMERA, + INPUT_USAGE_KEYCODE_CLEAR, + INPUT_USAGE_KEYCODE_A, + INPUT_USAGE_KEYCODE_B, + INPUT_USAGE_KEYCODE_C, + INPUT_USAGE_KEYCODE_D, + INPUT_USAGE_KEYCODE_E, + INPUT_USAGE_KEYCODE_F, + INPUT_USAGE_KEYCODE_G, + INPUT_USAGE_KEYCODE_H, + INPUT_USAGE_KEYCODE_I, + INPUT_USAGE_KEYCODE_J, + INPUT_USAGE_KEYCODE_K, + INPUT_USAGE_KEYCODE_L, + INPUT_USAGE_KEYCODE_M, + INPUT_USAGE_KEYCODE_N, + INPUT_USAGE_KEYCODE_O, + INPUT_USAGE_KEYCODE_P, + INPUT_USAGE_KEYCODE_Q, + INPUT_USAGE_KEYCODE_R, + INPUT_USAGE_KEYCODE_S, + INPUT_USAGE_KEYCODE_T, + INPUT_USAGE_KEYCODE_U, + INPUT_USAGE_KEYCODE_V, + INPUT_USAGE_KEYCODE_W, + INPUT_USAGE_KEYCODE_X, + INPUT_USAGE_KEYCODE_Y, + INPUT_USAGE_KEYCODE_Z, + INPUT_USAGE_KEYCODE_COMMA, + INPUT_USAGE_KEYCODE_PERIOD, + INPUT_USAGE_KEYCODE_ALT_LEFT, + INPUT_USAGE_KEYCODE_ALT_RIGHT, + INPUT_USAGE_KEYCODE_SHIFT_LEFT, + INPUT_USAGE_KEYCODE_SHIFT_RIGHT, + INPUT_USAGE_KEYCODE_TAB, + INPUT_USAGE_KEYCODE_SPACE, + INPUT_USAGE_KEYCODE_SYM, + INPUT_USAGE_KEYCODE_EXPLORER, + INPUT_USAGE_KEYCODE_ENVELOPE, + INPUT_USAGE_KEYCODE_ENTER, + INPUT_USAGE_KEYCODE_DEL, + INPUT_USAGE_KEYCODE_GRAVE, + INPUT_USAGE_KEYCODE_MINUS, + INPUT_USAGE_KEYCODE_EQUALS, + INPUT_USAGE_KEYCODE_LEFT_BRACKET, + INPUT_USAGE_KEYCODE_RIGHT_BRACKET, + INPUT_USAGE_KEYCODE_BACKSLASH, + INPUT_USAGE_KEYCODE_SEMICOLON, + INPUT_USAGE_KEYCODE_APOSTROPHE, + INPUT_USAGE_KEYCODE_SLASH, + INPUT_USAGE_KEYCODE_AT, + INPUT_USAGE_KEYCODE_NUM, + INPUT_USAGE_KEYCODE_HEADSETHOOK, + INPUT_USAGE_KEYCODE_FOCUS, // *Camera* focus + INPUT_USAGE_KEYCODE_PLUS, + INPUT_USAGE_KEYCODE_MENU, + INPUT_USAGE_KEYCODE_NOTIFICATION, + INPUT_USAGE_KEYCODE_SEARCH, + INPUT_USAGE_KEYCODE_MEDIA_PLAY_PAUSE, + INPUT_USAGE_KEYCODE_MEDIA_STOP, + INPUT_USAGE_KEYCODE_MEDIA_NEXT, + INPUT_USAGE_KEYCODE_MEDIA_PREVIOUS, + INPUT_USAGE_KEYCODE_MEDIA_REWIND, + INPUT_USAGE_KEYCODE_MEDIA_FAST_FORWARD, + INPUT_USAGE_KEYCODE_MUTE, + INPUT_USAGE_KEYCODE_PAGE_UP, + INPUT_USAGE_KEYCODE_PAGE_DOWN, + INPUT_USAGE_KEYCODE_PICTSYMBOLS, + INPUT_USAGE_KEYCODE_SWITCH_CHARSET, + INPUT_USAGE_KEYCODE_BUTTON_A, + INPUT_USAGE_KEYCODE_BUTTON_B, + INPUT_USAGE_KEYCODE_BUTTON_C, + INPUT_USAGE_KEYCODE_BUTTON_X, + INPUT_USAGE_KEYCODE_BUTTON_Y, + INPUT_USAGE_KEYCODE_BUTTON_Z, + INPUT_USAGE_KEYCODE_BUTTON_L1, + INPUT_USAGE_KEYCODE_BUTTON_R1, + INPUT_USAGE_KEYCODE_BUTTON_L2, + INPUT_USAGE_KEYCODE_BUTTON_R2, + INPUT_USAGE_KEYCODE_BUTTON_THUMBL, + INPUT_USAGE_KEYCODE_BUTTON_THUMBR, + INPUT_USAGE_KEYCODE_BUTTON_START, + INPUT_USAGE_KEYCODE_BUTTON_SELECT, + INPUT_USAGE_KEYCODE_BUTTON_MODE, + INPUT_USAGE_KEYCODE_ESCAPE, + INPUT_USAGE_KEYCODE_FORWARD_DEL, + INPUT_USAGE_KEYCODE_CTRL_LEFT, + INPUT_USAGE_KEYCODE_CTRL_RIGHT, + INPUT_USAGE_KEYCODE_CAPS_LOCK, + INPUT_USAGE_KEYCODE_SCROLL_LOCK, + INPUT_USAGE_KEYCODE_META_LEFT, + INPUT_USAGE_KEYCODE_META_RIGHT, + INPUT_USAGE_KEYCODE_FUNCTION, + INPUT_USAGE_KEYCODE_SYSRQ, + INPUT_USAGE_KEYCODE_BREAK, + INPUT_USAGE_KEYCODE_MOVE_HOME, + INPUT_USAGE_KEYCODE_MOVE_END, + INPUT_USAGE_KEYCODE_INSERT, + INPUT_USAGE_KEYCODE_FORWARD, + INPUT_USAGE_KEYCODE_MEDIA_PLAY, + INPUT_USAGE_KEYCODE_MEDIA_PAUSE, + INPUT_USAGE_KEYCODE_MEDIA_CLOSE, + INPUT_USAGE_KEYCODE_MEDIA_EJECT, + INPUT_USAGE_KEYCODE_MEDIA_RECORD, + INPUT_USAGE_KEYCODE_F1, + INPUT_USAGE_KEYCODE_F2, + INPUT_USAGE_KEYCODE_F3, + INPUT_USAGE_KEYCODE_F4, + INPUT_USAGE_KEYCODE_F5, + INPUT_USAGE_KEYCODE_F6, + INPUT_USAGE_KEYCODE_F7, + INPUT_USAGE_KEYCODE_F8, + INPUT_USAGE_KEYCODE_F9, + INPUT_USAGE_KEYCODE_F10, + INPUT_USAGE_KEYCODE_F11, + INPUT_USAGE_KEYCODE_F12, + INPUT_USAGE_KEYCODE_NUM_LOCK, + INPUT_USAGE_KEYCODE_NUMPAD_0, + INPUT_USAGE_KEYCODE_NUMPAD_1, + INPUT_USAGE_KEYCODE_NUMPAD_2, + INPUT_USAGE_KEYCODE_NUMPAD_3, + INPUT_USAGE_KEYCODE_NUMPAD_4, + INPUT_USAGE_KEYCODE_NUMPAD_5, + INPUT_USAGE_KEYCODE_NUMPAD_6, + INPUT_USAGE_KEYCODE_NUMPAD_7, + INPUT_USAGE_KEYCODE_NUMPAD_8, + INPUT_USAGE_KEYCODE_NUMPAD_9, + INPUT_USAGE_KEYCODE_NUMPAD_DIVIDE, + INPUT_USAGE_KEYCODE_NUMPAD_MULTIPLY, + INPUT_USAGE_KEYCODE_NUMPAD_SUBTRACT, + INPUT_USAGE_KEYCODE_NUMPAD_ADD, + INPUT_USAGE_KEYCODE_NUMPAD_DOT, + INPUT_USAGE_KEYCODE_NUMPAD_COMMA, + INPUT_USAGE_KEYCODE_NUMPAD_ENTER, + INPUT_USAGE_KEYCODE_NUMPAD_EQUALS, + INPUT_USAGE_KEYCODE_NUMPAD_LEFT_PAREN, + INPUT_USAGE_KEYCODE_NUMPAD_RIGHT_PAREN, + INPUT_USAGE_KEYCODE_VOLUME_MUTE, + INPUT_USAGE_KEYCODE_INFO, + INPUT_USAGE_KEYCODE_CHANNEL_UP, + INPUT_USAGE_KEYCODE_CHANNEL_DOWN, + INPUT_USAGE_KEYCODE_ZOOM_IN, + INPUT_USAGE_KEYCODE_ZOOM_OUT, + INPUT_USAGE_KEYCODE_TV, + INPUT_USAGE_KEYCODE_WINDOW, + INPUT_USAGE_KEYCODE_GUIDE, + INPUT_USAGE_KEYCODE_DVR, + INPUT_USAGE_KEYCODE_BOOKMARK, + INPUT_USAGE_KEYCODE_CAPTIONS, + INPUT_USAGE_KEYCODE_SETTINGS, + INPUT_USAGE_KEYCODE_TV_POWER, + INPUT_USAGE_KEYCODE_TV_INPUT, + INPUT_USAGE_KEYCODE_STB_POWER, + INPUT_USAGE_KEYCODE_STB_INPUT, + INPUT_USAGE_KEYCODE_AVR_POWER, + INPUT_USAGE_KEYCODE_AVR_INPUT, + INPUT_USAGE_KEYCODE_PROG_RED, + INPUT_USAGE_KEYCODE_PROG_GREEN, + INPUT_USAGE_KEYCODE_PROG_YELLOW, + INPUT_USAGE_KEYCODE_PROG_BLUE, + INPUT_USAGE_KEYCODE_APP_SWITCH, + INPUT_USAGE_KEYCODE_BUTTON_1, + INPUT_USAGE_KEYCODE_BUTTON_2, + INPUT_USAGE_KEYCODE_BUTTON_3, + INPUT_USAGE_KEYCODE_BUTTON_4, + INPUT_USAGE_KEYCODE_BUTTON_5, + INPUT_USAGE_KEYCODE_BUTTON_6, + INPUT_USAGE_KEYCODE_BUTTON_7, + INPUT_USAGE_KEYCODE_BUTTON_8, + INPUT_USAGE_KEYCODE_BUTTON_9, + INPUT_USAGE_KEYCODE_BUTTON_10, + INPUT_USAGE_KEYCODE_BUTTON_11, + INPUT_USAGE_KEYCODE_BUTTON_12, + INPUT_USAGE_KEYCODE_BUTTON_13, + INPUT_USAGE_KEYCODE_BUTTON_14, + INPUT_USAGE_KEYCODE_BUTTON_15, + INPUT_USAGE_KEYCODE_BUTTON_16, + INPUT_USAGE_KEYCODE_LANGUAGE_SWITCH, + INPUT_USAGE_KEYCODE_MANNER_MODE, + INPUT_USAGE_KEYCODE_3D_MODE, + INPUT_USAGE_KEYCODE_CONTACTS, + INPUT_USAGE_KEYCODE_CALENDAR, + INPUT_USAGE_KEYCODE_MUSIC, + INPUT_USAGE_KEYCODE_CALCULATOR, + INPUT_USAGE_KEYCODE_ZENKAKU_HANKAKU, + INPUT_USAGE_KEYCODE_EISU, + INPUT_USAGE_KEYCODE_MUHENKAN, + INPUT_USAGE_KEYCODE_HENKAN, + INPUT_USAGE_KEYCODE_KATAKANA_HIRAGANA, + INPUT_USAGE_KEYCODE_YEN, + INPUT_USAGE_KEYCODE_RO, + INPUT_USAGE_KEYCODE_KANA, + INPUT_USAGE_KEYCODE_ASSIST, + INPUT_USAGE_KEYCODE_BRIGHTNESS_DOWN, + INPUT_USAGE_KEYCODE_BRIGHTNESS_UP, + INPUT_USAGE_KEYCODE_MEDIA_AUDIO_TRACK, + INPUT_USAGE_KEYCODE_SLEEP, + INPUT_USAGE_KEYCODE_WAKEUP, + INPUT_USAGE_KEYCODE_PAIRING, + INPUT_USAGE_KEYCODE_MEDIA_TOP_MENU, + INPUT_USAGE_KEYCODE_11, + INPUT_USAGE_KEYCODE_12, + INPUT_USAGE_KEYCODE_LAST_CHANNEL, + INPUT_USAGE_KEYCODE_TV_DATA_SERVICE, + INPUT_USAGE_KEYCODE_VOICE_ASSIST, + INPUT_USAGE_KEYCODE_TV_RADIO_SERVICE, + INPUT_USAGE_KEYCODE_TV_TELETEXT, + INPUT_USAGE_KEYCODE_TV_NUMBER_ENTRY, + INPUT_USAGE_KEYCODE_TV_TERRESTRIAL_ANALOG, + INPUT_USAGE_KEYCODE_TV_TERRESTRIAL_DIGITAL, + INPUT_USAGE_KEYCODE_TV_SATELLITE, + INPUT_USAGE_KEYCODE_TV_SATELLITE_BS, + INPUT_USAGE_KEYCODE_TV_SATELLITE_CS, + INPUT_USAGE_KEYCODE_TV_SATELLITE_SERVICE, + INPUT_USAGE_KEYCODE_TV_NETWORK, + INPUT_USAGE_KEYCODE_TV_ANTENNA_CABLE, + INPUT_USAGE_KEYCODE_TV_INPUT_HDMI_1, + INPUT_USAGE_KEYCODE_TV_INPUT_HDMI_2, + INPUT_USAGE_KEYCODE_TV_INPUT_HDMI_3, + INPUT_USAGE_KEYCODE_TV_INPUT_HDMI_4, + INPUT_USAGE_KEYCODE_TV_INPUT_COMPOSITE_1, + INPUT_USAGE_KEYCODE_TV_INPUT_COMPOSITE_2, + INPUT_USAGE_KEYCODE_TV_INPUT_COMPONENT_1, + INPUT_USAGE_KEYCODE_TV_INPUT_COMPONENT_2, + INPUT_USAGE_KEYCODE_TV_INPUT_VGA_1, + INPUT_USAGE_KEYCODE_TV_AUDIO_DESCRIPTION, + INPUT_USAGE_KEYCODE_TV_AUDIO_DESCRIPTION_MIX_UP, + INPUT_USAGE_KEYCODE_TV_AUDIO_DESCRIPTION_MIX_DOWN, + INPUT_USAGE_KEYCODE_TV_ZOOM_MODE, + INPUT_USAGE_KEYCODE_TV_CONTENTS_MENU, + INPUT_USAGE_KEYCODE_TV_MEDIA_CONTEXT_MENU, + INPUT_USAGE_KEYCODE_TV_TIMER_PROGRAMMING, + INPUT_USAGE_KEYCODE_HELP, + + // axes + INPUT_USAGE_AXIS_X, + INPUT_USAGE_AXIS_Y, + INPUT_USAGE_AXIS_PRESSURE, + INPUT_USAGE_AXIS_SIZE, + INPUT_USAGE_AXIS_TOUCH_MAJOR, + INPUT_USAGE_AXIS_TOUCH_MINOR, + INPUT_USAGE_AXIS_TOOL_MAJOR, + INPUT_USAGE_AXIS_TOOL_MINOR, + INPUT_USAGE_AXIS_ORIENTATION, + INPUT_USAGE_AXIS_VSCROLL, + INPUT_USAGE_AXIS_HSCROLL, + INPUT_USAGE_AXIS_Z, + INPUT_USAGE_AXIS_RX, + INPUT_USAGE_AXIS_RY, + INPUT_USAGE_AXIS_RZ, + INPUT_USAGE_AXIS_HAT_X, + INPUT_USAGE_AXIS_HAT_Y, + INPUT_USAGE_AXIS_LTRIGGER, + INPUT_USAGE_AXIS_RTRIGGER, + INPUT_USAGE_AXIS_THROTTLE, + INPUT_USAGE_AXIS_RUDDER, + INPUT_USAGE_AXIS_WHEEL, + INPUT_USAGE_AXIS_GAS, + INPUT_USAGE_AXIS_BRAKE, + INPUT_USAGE_AXIS_DISTANCE, + INPUT_USAGE_AXIS_TILT, + INPUT_USAGE_AXIS_GENERIC_1, + INPUT_USAGE_AXIS_GENERIC_2, + INPUT_USAGE_AXIS_GENERIC_3, + INPUT_USAGE_AXIS_GENERIC_4, + INPUT_USAGE_AXIS_GENERIC_5, + INPUT_USAGE_AXIS_GENERIC_6, + INPUT_USAGE_AXIS_GENERIC_7, + INPUT_USAGE_AXIS_GENERIC_8, + INPUT_USAGE_AXIS_GENERIC_9, + INPUT_USAGE_AXIS_GENERIC_10, + INPUT_USAGE_AXIS_GENERIC_11, + INPUT_USAGE_AXIS_GENERIC_12, + INPUT_USAGE_AXIS_GENERIC_13, + INPUT_USAGE_AXIS_GENERIC_14, + INPUT_USAGE_AXIS_GENERIC_15, + INPUT_USAGE_AXIS_GENERIC_16, + + // leds + INPUT_USAGE_LED_NUM_LOCK, + INPUT_USAGE_LED_CAPS_LOCK, + INPUT_USAGE_LED_SCROLL_LOCK, + INPUT_USAGE_LED_COMPOSE, + INPUT_USAGE_LED_KANA, + INPUT_USAGE_LED_SLEEP, + INPUT_USAGE_LED_SUSPEND, + INPUT_USAGE_LED_MUTE, + INPUT_USAGE_LED_MISC, + INPUT_USAGE_LED_MAIL, + INPUT_USAGE_LED_CHARGING, + INPUT_USAGE_LED_CONTROLLER_1, + INPUT_USAGE_LED_CONTROLLER_2, + INPUT_USAGE_LED_CONTROLLER_3, + INPUT_USAGE_LED_CONTROLLER_4, +} input_usage_t; + +typedef enum { + INPUT_COLLECTION_ID_TOUCH, + INPUT_COLLECTION_ID_KEYBOARD, + INPUT_COLLECTION_ID_MOUSE, + INPUT_COLLECTION_ID_TOUCHPAD, + // etc +} input_collection_id_t; + +typedef struct input_message input_message_t; + +typedef struct input_host_callbacks { + + /** + * Creates a device identifier with the given properties. + * The unique ID should be a string that precisely identifies a given piece of hardware. For + * example, an input device connected via Bluetooth could use its MAC address as its unique ID. + */ + input_device_identifier_t* (*create_device_identifier)(input_host_t* host, + const char* name, int32_t product_id, int32_t vendor_id, + input_bus_t bus, const char* unique_id); + + /** + * Allocates the device definition which will describe the input capabilities of a device. A + * device definition may be used to register as many devices as desired. + */ + input_device_definition_t* (*create_device_definition)(input_host_t* host); + + /** + * Allocate either an input report, which the HAL will use to tell the host of incoming input + * events, or an output report, which the host will use to tell the HAL of desired state + * changes (e.g. setting an LED). + */ + input_report_definition_t* (*create_input_report_definition)(input_host_t* host); + input_report_definition_t* (*create_output_report_definition)(input_host_t* host); + + /** + * Append the report to the given input device. + */ + void (*input_device_definition_add_report)(input_host_t* host, + input_device_definition_t* d, input_report_definition_t* r); + + /** + * Add a collection with the given arity and ID. A collection describes a set + * of logically grouped properties such as the X and Y coordinates of a single finger touch or + * the set of keys on a keyboard. The arity declares how many repeated instances of this + * collection will appear in whatever report it is attached to. The ID describes the type of + * grouping being represented by the collection. For example, a touchscreen capable of + * reporting up to 2 fingers simultaneously might have a collection with the X and Y + * coordinates, an arity of 2, and an ID of INPUT_COLLECTION_USAGE_TOUCHSCREEN. Any given ID + * may only be present once for a given report. + */ + void (*input_report_definition_add_collection)(input_host_t* host, + input_report_definition_t* report, input_collection_id_t id, int32_t arity); + + /** + * Declare an int usage with the given properties. The report and collection defines where the + * usage is being declared. + */ + void (*input_report_definition_declare_usage_int)(input_host_t* host, + input_report_definition_t* report, input_collection_id_t id, + input_usage_t usage, int32_t min, int32_t max, float resolution); + + /** + * Declare a set of boolean usages with the given properties. The report and collection + * defines where the usages are being declared. + */ + void (*input_report_definition_declare_usages_bool)(input_host_t* host, + input_report_definition_t* report, input_collection_id_t id, + input_usage_t* usage, size_t usage_count); + + + /** + * Register a given input device definition. This notifies the host that an input device has + * been connected and gives a description of all its capabilities. + */ + input_device_handle_t* (*register_device)(input_host_t* host, + input_device_identifier_t* id, input_device_definition_t* d); + + /** Unregister the given device */ + void (*unregister_device)(input_host_t* host, input_device_handle_t* handle); + + /** + * Allocate a report that will contain all of the state as described by the given report. + */ + input_report_t* (*input_allocate_report)(input_host_t* host, input_report_definition_t* r); + + /** + * Add an int usage value to a report. + */ + void (*input_report_set_usage_int)(input_host_t* host, input_report_t* r, + input_collection_id_t id, input_usage_t usage, int32_t value, int32_t arity_index); + + /** + * Add a boolean usage value to a report. + */ + void (*input_report_set_usage_bool)(input_host_t* host, input_report_t* r, + input_collection_id_t id, input_usage_t usage, bool value, int32_t arity_index); + + void (*report_event)(input_host_t* host, input_device_handle_t* d, input_report_t* report); + + /** + * Retrieve the set of properties for the device. The returned + * input_property_map_t* may be used to query specific properties via the + * input_get_device_property callback. + */ + input_property_map_t* (*input_get_device_property_map)(input_host_t* host, + input_device_identifier_t* id); + /** + * Retrieve a property for the device with the given key. Returns NULL if + * the key does not exist, or an input_property_t* that must be freed using + * input_free_device_property(). Using an input_property_t after the + * corresponding input_property_map_t is freed is undefined. + */ + input_property_t* (*input_get_device_property)(input_host_t* host, + input_property_map_t* map, const char* key); + + /** + * Get the key for the input property. Returns NULL if the property is NULL. + * The returned const char* is owned by the input_property_t. + */ + const char* (*input_get_property_key)(input_host_t* host, input_property_t* property); + + /** + * Get the value for the input property. Returns NULL if the property is + * NULL. The returned const char* is owned by the input_property_t. + */ + const char* (*input_get_property_value)(input_host_t* host, input_property_t* property); + + /** + * Frees the input_property_t*. + */ + void (*input_free_device_property)(input_host_t* host, input_property_t* property); + + /** + * Frees the input_property_map_t*. + */ + void (*input_free_device_property_map)(input_host_t* host, input_property_map_t* map); +} input_host_callbacks_t; + +typedef struct input_module input_module_t; + +struct input_module { + /** + * Common methods of the input module. This *must* be the first member + * of input_module as users of this structure will cast a hw_module_t + * to input_module pointer in contexts where it's known + * the hw_module_t references a input_module. + */ + struct hw_module_t common; + + /** + * Initialize the module with host callbacks. At this point the HAL should start up whatever + * infrastructure it needs to in order to process input events. + */ + void (*init)(const input_module_t* module, input_host_t* host, input_host_callbacks_t cb); + + /** + * Sends an output report with a new set of state the host would like the given device to + * assume. + */ + void (*notify_report)(const input_module_t* module, input_report_t* report); +}; + +static inline int input_open(const struct hw_module_t** module, const char* type) { + return hw_get_module_by_class(INPUT_HARDWARE_MODULE_ID, type, module); +} + +__END_DECLS + +#endif /* ANDROID_INCLUDE_HARDWARE_INPUT_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/keymaster0.h b/third_party/android_hardware_libhardware/include/hardware/keymaster0.h new file mode 100644 index 00000000000000..f020e5b188a838 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/keymaster0.h @@ -0,0 +1,149 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_HARDWARE_KEYMASTER_0_H +#define ANDROID_HARDWARE_KEYMASTER_0_H + +#include + +__BEGIN_DECLS + +/** + * Keymaster0 device definition. + */ +struct keymaster0_device { + /** + * Common methods of the keymaster device. This *must* be the first member of + * keymaster0_device as users of this structure will cast a hw_device_t to + * keymaster0_device pointer in contexts where it's known the hw_device_t references a + * keymaster0_device. + */ + struct hw_device_t common; + + /** + * THIS IS DEPRECATED. Use the new "module_api_version" and "hal_api_version" + * fields in the keymaster_module initialization instead. + */ + uint32_t client_version; + + /** + * See flags defined for keymaster0_device::flags in keymaster_common.h + */ + uint32_t flags; + + void* context; + + /** + * Generates a public and private key. The key-blob returned is opaque + * and must subsequently provided for signing and verification. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*generate_keypair)(const struct keymaster0_device* dev, + const keymaster_keypair_t key_type, const void* key_params, + uint8_t** key_blob, size_t* key_blob_length); + + /** + * Imports a public and private key pair. The imported keys will be in + * PKCS#8 format with DER encoding (Java standard). The key-blob + * returned is opaque and will be subsequently provided for signing + * and verification. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*import_keypair)(const struct keymaster0_device* dev, + const uint8_t* key, const size_t key_length, + uint8_t** key_blob, size_t* key_blob_length); + + /** + * Gets the public key part of a key pair. The public key must be in + * X.509 format (Java standard) encoded byte array. + * + * Returns: 0 on success or an error code less than 0. + * On error, x509_data should not be allocated. + */ + int (*get_keypair_public)(const struct keymaster0_device* dev, + const uint8_t* key_blob, const size_t key_blob_length, + uint8_t** x509_data, size_t* x509_data_length); + + /** + * Deletes the key pair associated with the key blob. + * + * This function is optional and should be set to NULL if it is not + * implemented. + * + * Returns 0 on success or an error code less than 0. + */ + int (*delete_keypair)(const struct keymaster0_device* dev, + const uint8_t* key_blob, const size_t key_blob_length); + + /** + * Deletes all keys in the hardware keystore. Used when keystore is + * reset completely. + * + * This function is optional and should be set to NULL if it is not + * implemented. + * + * Returns 0 on success or an error code less than 0. + */ + int (*delete_all)(const struct keymaster0_device* dev); + + /** + * Signs data using a key-blob generated before. This can use either + * an asymmetric key or a secret key. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*sign_data)(const struct keymaster0_device* dev, + const void* signing_params, + const uint8_t* key_blob, const size_t key_blob_length, + const uint8_t* data, const size_t data_length, + uint8_t** signed_data, size_t* signed_data_length); + + /** + * Verifies data signed with a key-blob. This can use either + * an asymmetric key or a secret key. + * + * Returns: 0 on successful verification or an error code less than 0. + */ + int (*verify_data)(const struct keymaster0_device* dev, + const void* signing_params, + const uint8_t* key_blob, const size_t key_blob_length, + const uint8_t* signed_data, const size_t signed_data_length, + const uint8_t* signature, const size_t signature_length); +}; +typedef struct keymaster0_device keymaster0_device_t; + + +/* Convenience API for opening and closing keymaster devices */ + +static inline int keymaster0_open(const struct hw_module_t* module, + keymaster0_device_t** device) +{ + int rc = module->methods->open(module, KEYSTORE_KEYMASTER, + (struct hw_device_t**) device); + + return rc; +} + +static inline int keymaster0_close(keymaster0_device_t* device) +{ + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_HARDWARE_KEYMASTER_0_H diff --git a/third_party/android_hardware_libhardware/include/hardware/keymaster1.h b/third_party/android_hardware_libhardware/include/hardware/keymaster1.h new file mode 100644 index 00000000000000..ac2cc2b4083524 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/keymaster1.h @@ -0,0 +1,597 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_HARDWARE_KEYMASTER1_H +#define ANDROID_HARDWARE_KEYMASTER1_H + +#include +#include + +__BEGIN_DECLS + +/** + * Keymaster1 device definition + */ +struct keymaster1_device { + /** + * Common methods of the keymaster device. This *must* be the first member of + * keymaster_device as users of this structure will cast a hw_device_t to + * keymaster_device pointer in contexts where it's known the hw_device_t references a + * keymaster_device. + */ + struct hw_device_t common; + + /** + * THIS IS DEPRECATED. Use the new "module_api_version" and "hal_api_version" + * fields in the keymaster_module initialization instead. + */ + uint32_t client_version; + + /** + * See flags defined for keymaster0_devices::flags in keymaster_common.h + */ + uint32_t flags; + + void* context; + + /** + * \deprecated Generates a public and private key. The key-blob returned is opaque and must + * subsequently provided for signing and verification. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*generate_keypair)(const struct keymaster1_device* dev, const keymaster_keypair_t key_type, + const void* key_params, uint8_t** key_blob, size_t* key_blob_length); + + /** + * \deprecated Imports a public and private key pair. The imported keys will be in PKCS#8 format + * with DER encoding (Java standard). The key-blob returned is opaque and will be subsequently + * provided for signing and verification. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*import_keypair)(const struct keymaster1_device* dev, const uint8_t* key, + const size_t key_length, uint8_t** key_blob, size_t* key_blob_length); + + /** + * \deprecated Gets the public key part of a key pair. The public key must be in X.509 format + * (Java standard) encoded byte array. + * + * Returns: 0 on success or an error code less than 0. On error, x509_data + * should not be allocated. + */ + int (*get_keypair_public)(const struct keymaster1_device* dev, const uint8_t* key_blob, + const size_t key_blob_length, uint8_t** x509_data, + size_t* x509_data_length); + + /** + * \deprecated Deletes the key pair associated with the key blob. + * + * This function is optional and should be set to NULL if it is not + * implemented. + * + * Returns 0 on success or an error code less than 0. + */ + int (*delete_keypair)(const struct keymaster1_device* dev, const uint8_t* key_blob, + const size_t key_blob_length); + + /** + * \deprecated Deletes all keys in the hardware keystore. Used when keystore is reset + * completely. + * + * This function is optional and should be set to NULL if it is not + * implemented. + * + * Returns 0 on success or an error code less than 0. + */ + int (*delete_all)(const struct keymaster1_device* dev); + + /** + * \deprecated Signs data using a key-blob generated before. This can use either an asymmetric + * key or a secret key. + * + * Returns: 0 on success or an error code less than 0. + */ + int (*sign_data)(const struct keymaster1_device* dev, const void* signing_params, + const uint8_t* key_blob, const size_t key_blob_length, const uint8_t* data, + const size_t data_length, uint8_t** signed_data, size_t* signed_data_length); + + /** + * \deprecated Verifies data signed with a key-blob. This can use either an asymmetric key or a + * secret key. + * + * Returns: 0 on successful verification or an error code less than 0. + */ + int (*verify_data)(const struct keymaster1_device* dev, const void* signing_params, + const uint8_t* key_blob, const size_t key_blob_length, + const uint8_t* signed_data, const size_t signed_data_length, + const uint8_t* signature, const size_t signature_length); + + /** + * Gets algorithms supported. + * + * \param[in] dev The keymaster device structure. + * + * \param[out] algorithms Array of algorithms supported. The caller takes ownership of the + * array and must free() it. + * + * \param[out] algorithms_length Length of \p algorithms. + */ + keymaster_error_t (*get_supported_algorithms)(const struct keymaster1_device* dev, + keymaster_algorithm_t** algorithms, + size_t* algorithms_length); + + /** + * Gets the block modes supported for the specified algorithm. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] algorithm The algorithm for which supported modes will be returned. + * + * \param[out] modes Array of modes supported. The caller takes ownership of the array and must + * free() it. + * + * \param[out] modes_length Length of \p modes. + */ + keymaster_error_t (*get_supported_block_modes)(const struct keymaster1_device* dev, + keymaster_algorithm_t algorithm, + keymaster_purpose_t purpose, + keymaster_block_mode_t** modes, + size_t* modes_length); + + /** + * Gets the padding modes supported for the specified algorithm. Caller assumes ownership of + * the allocated array. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] algorithm The algorithm for which supported padding modes will be returned. + * + * \param[out] modes Array of padding modes supported. The caller takes ownership of the array + * and must free() it. + * + * \param[out] modes_length Length of \p modes. + */ + keymaster_error_t (*get_supported_padding_modes)(const struct keymaster1_device* dev, + keymaster_algorithm_t algorithm, + keymaster_purpose_t purpose, + keymaster_padding_t** modes, + size_t* modes_length); + + /** + * Gets the digests supported for the specified algorithm. Caller assumes ownership of the + * allocated array. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] algorithm The algorithm for which supported digests will be returned. + * + * \param[out] digests Array of digests supported. The caller takes ownership of the array and + * must free() it. + * + * \param[out] digests_length Length of \p digests. + */ + keymaster_error_t (*get_supported_digests)(const struct keymaster1_device* dev, + keymaster_algorithm_t algorithm, + keymaster_purpose_t purpose, + keymaster_digest_t** digests, + size_t* digests_length); + + /** + * Gets the key import formats supported for keys of the specified algorithm. Caller assumes + * ownership of the allocated array. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] algorithm The algorithm for which supported formats will be returned. + * + * \param[out] formats Array of formats supported. The caller takes ownership of the array and + * must free() it. + * + * \param[out] formats_length Length of \p formats. + */ + keymaster_error_t (*get_supported_import_formats)(const struct keymaster1_device* dev, + keymaster_algorithm_t algorithm, + keymaster_key_format_t** formats, + size_t* formats_length); + + /** + * Gets the key export formats supported for keys of the specified algorithm. Caller assumes + * ownership of the allocated array. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] algorithm The algorithm for which supported formats will be returned. + * + * \param[out] formats Array of formats supported. The caller takes ownership of the array and + * must free() it. + * + * \param[out] formats_length Length of \p formats. + */ + keymaster_error_t (*get_supported_export_formats)(const struct keymaster1_device* dev, + keymaster_algorithm_t algorithm, + keymaster_key_format_t** formats, + size_t* formats_length); + + /** + * Adds entropy to the RNG used by keymaster. Entropy added through this method is guaranteed + * not to be the only source of entropy used, and the mixing function is required to be secure, + * in the sense that if the RNG is seeded (from any source) with any data the attacker cannot + * predict (or control), then the RNG output is indistinguishable from random. Thus, if the + * entropy from any source is good, the output will be good. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] data Random data to be mixed in. + * + * \param[in] data_length Length of \p data. + */ + keymaster_error_t (*add_rng_entropy)(const struct keymaster1_device* dev, const uint8_t* data, + size_t data_length); + + /** + * Generates a key, or key pair, returning a key blob and/or a description of the key. + * + * Key generation parameters are defined as keymaster tag/value pairs, provided in \p params. + * See keymaster_tag_t for the full list. Some values that are always required for generation + * of useful keys are: + * + * - KM_TAG_ALGORITHM; + * - KM_TAG_PURPOSE; and + * - (KM_TAG_USER_SECURE_ID and KM_TAG_USER_AUTH_TYPE) or KM_TAG_NO_AUTH_REQUIRED. + * + * KM_TAG_AUTH_TIMEOUT should generally be specified unless KM_TAG_NO_AUTH_REQUIRED is present, + * or the user will have to authenticate for every use. + * + * KM_TAG_BLOCK_MODE, KM_TAG_PADDING, KM_TAG_MAC_LENGTH and KM_TAG_DIGEST must be specified for + * algorithms that require them. + * + * The following tags may not be specified; their values will be provided by the implementation. + * + * - KM_TAG_ORIGIN, + * - KM_TAG_ROLLBACK_RESISTANT, + * - KM_TAG_CREATION_DATETIME + * + * \param[in] dev The keymaster device structure. + * + * \param[in] params Array of key generation parameters. + * + * \param[in] params_count Length of \p params. + * + * \param[out] key_blob returns the generated key. \p key_blob must not be NULL. The caller + * assumes ownership key_blob->key_material and must free() it. + * + * \param[out] characteristics returns the characteristics of the key that was, generated, if + * non-NULL. If non-NULL, the caller assumes ownership and must deallocate with + * keymaster_free_characteristics(). Note that KM_TAG_ROOT_OF_TRUST, KM_TAG_APPLICATION_ID and + * KM_TAG_APPLICATION_DATA are never returned. + */ + keymaster_error_t (*generate_key)(const struct keymaster1_device* dev, + const keymaster_key_param_set_t* params, + keymaster_key_blob_t* key_blob, + keymaster_key_characteristics_t** characteristics); + + /** + * Returns the characteristics of the specified key, or KM_ERROR_INVALID_KEY_BLOB if the + * key_blob is invalid (implementations must fully validate the integrity of the key). + * client_id and app_data must be the ID and data provided when the key was generated or + * imported, or empty if KM_TAG_APPLICATION_ID and/or KM_TAG_APPLICATION_DATA were not provided + * during generation. Those values are not included in the returned characteristics. The + * caller assumes ownership of the allocated characteristics object, which must be deallocated + * with keymaster_free_characteristics(). + * + * Note that KM_TAG_ROOT_OF_TRUST, KM_TAG_APPLICATION_ID and KM_TAG_APPLICATION_DATA are never + * returned. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] key_blob The key to retreive characteristics from. + * + * \param[in] client_id The client ID data, or NULL if none associated. + * + * \param[in] app_id The app data, or NULL if none associated. + * + * \param[out] characteristics The key characteristics. + */ + keymaster_error_t (*get_key_characteristics)(const struct keymaster1_device* dev, + const keymaster_key_blob_t* key_blob, + const keymaster_blob_t* client_id, + const keymaster_blob_t* app_data, + keymaster_key_characteristics_t** characteristics); + + /** + * Imports a key, or key pair, returning a key blob and/or a description of the key. + * + * Most key import parameters are defined as keymaster tag/value pairs, provided in "params". + * See keymaster_tag_t for the full list. Values that are always required for import of useful + * keys are: + * + * - KM_TAG_ALGORITHM; + * - KM_TAG_PURPOSE; and + * - (KM_TAG_USER_SECURE_ID and KM_TAG_USER_AUTH_TYPE) or KM_TAG_NO_AUTH_REQUIRED. + * + * KM_TAG_AUTH_TIMEOUT should generally be specified. If unspecified, the user will have to + * authenticate for every use. + * + * The following tags will take default values if unspecified: + * + * - KM_TAG_KEY_SIZE will default to the size of the key provided. + * - KM_TAG_RSA_PUBLIC_EXPONENT will default to the value in the key provided (for RSA keys) + * + * The following tags may not be specified; their values will be provided by the implementation. + * + * - KM_TAG_ORIGIN, + * - KM_TAG_ROLLBACK_RESISTANT, + * - KM_TAG_CREATION_DATETIME + * + * \param[in] dev The keymaster device structure. + * + * \param[in] params Parameters defining the imported key. + * + * \param[in] params_count The number of entries in \p params. + * + * \param[in] key_format specifies the format of the key data in key_data. + * + * \param[out] key_blob Used to return the opaque key blob. Must be non-NULL. The caller + * assumes ownership of the contained key_material. + * + * \param[out] characteristics Used to return the characteristics of the imported key. May be + * NULL, in which case no characteristics will be returned. If non-NULL, the caller assumes + * ownership and must deallocate with keymaster_free_characteristics(). Note that + * KM_TAG_ROOT_OF_TRUST, KM_TAG_APPLICATION_ID and + * KM_TAG_APPLICATION_DATA are never returned. + */ + keymaster_error_t (*import_key)(const struct keymaster1_device* dev, + const keymaster_key_param_set_t* params, + keymaster_key_format_t key_format, + const keymaster_blob_t* key_data, + keymaster_key_blob_t* key_blob, + keymaster_key_characteristics_t** characteristics); + + /** + * Exports a public key, returning a byte array in the specified format. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] export_format The format to be used for exporting the key. + * + * \param[in] key_to_export The key to export. + * + * \param[out] export_data The exported key material. The caller assumes ownership. + * + * \param[out] export_data_length The length of \p export_data. + */ + keymaster_error_t (*export_key)(const struct keymaster1_device* dev, + keymaster_key_format_t export_format, + const keymaster_key_blob_t* key_to_export, + const keymaster_blob_t* client_id, + const keymaster_blob_t* app_data, + keymaster_blob_t* export_data); + + /** + * Deletes the key, or key pair, associated with the key blob. After calling this function it + * will be impossible to use the key for any other operations. May be applied to keys from + * foreign roots of trust (keys not usable under the current root of trust). + * + * This function is optional and should be set to NULL if it is not implemented. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] key The key to be deleted. + */ + keymaster_error_t (*delete_key)(const struct keymaster1_device* dev, + const keymaster_key_blob_t* key); + + /** + * Deletes all keys in the hardware keystore. Used when keystore is reset completely. After + * calling this function it will be impossible to use any previously generated or imported key + * blobs for any operations. + * + * This function is optional and should be set to NULL if it is not implemented. + * + * \param[in] dev The keymaster device structure. + */ + keymaster_error_t (*delete_all_keys)(const struct keymaster1_device* dev); + + /** + * Begins a cryptographic operation using the specified key. If all is well, begin() will + * return KM_ERROR_OK and create an operation handle which must be passed to subsequent calls to + * update(), finish() or abort(). + * + * It is critical that each call to begin() be paired with a subsequent call to finish() or + * abort(), to allow the keymaster implementation to clean up any internal operation state. + * Failure to do this may leak internal state space or other internal resources and may + * eventually cause begin() to return KM_ERROR_TOO_MANY_OPERATIONS when it runs out of space for + * operations. Any result other than KM_ERROR_OK from begin(), update() or finish() implicitly + * aborts the operation, in which case abort() need not be called (and will return + * KM_ERROR_INVALID_OPERATION_HANDLE if called). + * + * \param[in] dev The keymaster device structure. + * + * \param[in] purpose The purpose of the operation, one of KM_PURPOSE_ENCRYPT, + * KM_PURPOSE_DECRYPT, KM_PURPOSE_SIGN or KM_PURPOSE_VERIFY. Note that for AEAD modes, + * encryption and decryption imply signing and verification, respectively, but should be + * specified as KM_PURPOSE_ENCRYPT and KM_PURPOSE_DECRYPT. + * + * \param[in] key The key to be used for the operation. \p key must have a purpose compatible + * with \p purpose and all of its usage requirements must be satisfied, or begin() will return + * an appropriate error code. + * + * \param[in] in_params Additional parameters for the operation. This is typically used to + * provide authentication data, with KM_TAG_AUTH_TOKEN. If KM_TAG_APPLICATION_ID or + * KM_TAG_APPLICATION_DATA were provided during generation, they must be provided here, or the + * operation will fail with KM_ERROR_INVALID_KEY_BLOB. For operations that require a nonce or + * IV, on keys that were generated with KM_TAG_CALLER_NONCE, in_params may contain a tag + * KM_TAG_NONCE. For AEAD operations KM_TAG_CHUNK_SIZE is specified here. + * + * \param[out] out_params Output parameters. Used to return additional data from the operation + * initialization, notably to return the IV or nonce from operations that generate an IV or + * nonce. The caller takes ownership of the output parameters array and must free it with + * keymaster_free_param_set(). out_params may be set to NULL if no output parameters are + * expected. If out_params is NULL, and output paramaters are generated, begin() will return + * KM_ERROR_OUTPUT_PARAMETER_NULL. + * + * \param[out] operation_handle The newly-created operation handle which must be passed to + * update(), finish() or abort(). If operation_handle is NULL, begin() will return + * KM_ERROR_OUTPUT_PARAMETER_NULL. + */ + keymaster_error_t (*begin)(const struct keymaster1_device* dev, keymaster_purpose_t purpose, + const keymaster_key_blob_t* key, + const keymaster_key_param_set_t* in_params, + keymaster_key_param_set_t* out_params, + keymaster_operation_handle_t* operation_handle); + + /** + * Provides data to, and possibly receives output from, an ongoing cryptographic operation begun + * with begin(). + * + * If operation_handle is invalid, update() will return KM_ERROR_INVALID_OPERATION_HANDLE. + * + * update() may not consume all of the data provided in the data buffer. update() will return + * the amount consumed in *data_consumed. The caller should provide the unconsumed data in a + * subsequent call. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] operation_handle The operation handle returned by begin(). + * + * \param[in] in_params Additional parameters for the operation. For AEAD modes, this is used + * to specify KM_TAG_ADDITIONAL_DATA. Note that additional data may be provided in multiple + * calls to update(), but only until input data has been provided. + * + * \param[in] input Data to be processed, per the parameters established in the call to begin(). + * Note that update() may or may not consume all of the data provided. See \p input_consumed. + * + * \param[out] input_consumed Amount of data that was consumed by update(). If this is less + * than the amount provided, the caller should provide the remainder in a subsequent call to + * update(). + * + * \param[out] out_params Output parameters. Used to return additional data from the operation + * The caller takes ownership of the output parameters array and must free it with + * keymaster_free_param_set(). out_params may be set to NULL if no output parameters are + * expected. If out_params is NULL, and output paramaters are generated, begin() will return + * KM_ERROR_OUTPUT_PARAMETER_NULL. + * + * \param[out] output The output data, if any. The caller assumes ownership of the allocated + * buffer. output must not be NULL. + * + * Note that update() may not provide any output, in which case output->data_length will be + * zero, and output->data may be either NULL or zero-length (so the caller should always free() + * it). + */ + keymaster_error_t (*update)(const struct keymaster1_device* dev, + keymaster_operation_handle_t operation_handle, + const keymaster_key_param_set_t* in_params, + const keymaster_blob_t* input, size_t* input_consumed, + keymaster_key_param_set_t* out_params, keymaster_blob_t* output); + + /** + * Finalizes a cryptographic operation begun with begin() and invalidates \p operation_handle. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] operation_handle The operation handle returned by begin(). This handle will be + * invalidated. + * + * \param[in] params Additional parameters for the operation. For AEAD modes, this is used to + * specify KM_TAG_ADDITIONAL_DATA, but only if no input data was provided to update(). + * + * \param[in] signature The signature to be verified if the purpose specified in the begin() + * call was KM_PURPOSE_VERIFY. + * + * \param[out] output The output data, if any. The caller assumes ownership of the allocated + * buffer. + * + * If the operation being finished is a signature verification or an AEAD-mode decryption and + * verification fails then finish() will return KM_ERROR_VERIFICATION_FAILED. + */ + keymaster_error_t (*finish)(const struct keymaster1_device* dev, + keymaster_operation_handle_t operation_handle, + const keymaster_key_param_set_t* in_params, + const keymaster_blob_t* signature, + keymaster_key_param_set_t* out_params, keymaster_blob_t* output); + + /** + * Aborts a cryptographic operation begun with begin(), freeing all internal resources and + * invalidating \p operation_handle. + */ + keymaster_error_t (*abort)(const struct keymaster1_device* dev, + keymaster_operation_handle_t operation_handle); + + /** + * Generates a pair of ATTK defined in SOTER. Save the private key into RPMB. + * Note that the ATTK generated will never be touched outside the keymaster. + * + * \param[in] dev The keymaster device structure. + * + * \param[in] copy_num The number of copies that will be saved in the RPMB. + */ + keymaster_error_t (*generate_attk_key_pair)(const struct keymaster1_device* dev, + const uint8_t copy_num); + + /** + * Verify the existance ATTK defined in SOTER. + * + * \param[in] dev The keymaster device structure. + * + * Returns: 0 if the ATTK exists. + */ + keymaster_error_t (*verify_attk_key_pair)(const struct keymaster1_device* dev); + + /** + * Export the public key of ATTK in PEM format. + * + * \param[in] dev The keymaster device structure. + * + * \param[out] pub_key_data The public key data in X.509v3 format PEM encoded + * + * \param[out] pub_key_data_length The length of the public key data. + */ + keymaster_error_t (*export_attk_public_key)(const struct keymaster1_device* dev, + const uint8_t* pub_key_data, + const size_t pub_key_data_length); + + /** + * Get Unique device ID. + * + * \param[in] dev The keymaster device structure. + * + * \param[out] device_id The unique id for each device, format as below: + * 1.bytes 0-3: Identify each silicon provider id. + * 2.bytes 4-7: SoC model ID, defined by each silicon provider + * 3.bytes 8-15: Public Chip Serial *Number of SoC, defined by each silicon provider + * + * \param[out] device_id_length The length of the device id. + */ + keymaster_error_t (*get_device_id)(const struct keymaster1_device* dev, + const uint8_t* device_id, + const size_t device_id_length); +}; +typedef struct keymaster1_device keymaster1_device_t; + +/* Convenience API for opening and closing keymaster devices */ + +static inline int keymaster1_open(const struct hw_module_t* module, keymaster1_device_t** device) { + return module->methods->open(module, KEYSTORE_KEYMASTER, (struct hw_device_t**)device); +} + +static inline int keymaster1_close(keymaster1_device_t* device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_HARDWARE_KEYMASTER1_H diff --git a/third_party/android_hardware_libhardware/include/hardware/keymaster_common.h b/third_party/android_hardware_libhardware/include/hardware/keymaster_common.h new file mode 100644 index 00000000000000..772d7e4d238680 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/keymaster_common.h @@ -0,0 +1,185 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_HARDWARE_KEYMASTER_COMMON_H +#define ANDROID_HARDWARE_KEYMASTER_COMMON_H + +#include +#include +#include + +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define KEYSTORE_HARDWARE_MODULE_ID "keystore" + +#define KEYSTORE_KEYMASTER "keymaster" + + +/** + * Settings for "module_api_version" and "hal_api_version" + * fields in the keymaster_module initialization. + */ + +/** + * Keymaster 0.X module version provide the same APIs, but later versions add more options + * for algorithms and flags. + */ +#define KEYMASTER_MODULE_API_VERSION_0_2 HARDWARE_MODULE_API_VERSION(0, 2) +#define KEYMASTER_DEVICE_API_VERSION_0_2 HARDWARE_DEVICE_API_VERSION(0, 2) + +#define KEYMASTER_MODULE_API_VERSION_0_3 HARDWARE_MODULE_API_VERSION(0, 3) +#define KEYMASTER_DEVICE_API_VERSION_0_3 HARDWARE_DEVICE_API_VERSION(0, 3) + +/** + * Keymaster 1.0 module version provides a completely different API, incompatible with 0.X. + */ +#define KEYMASTER_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define KEYMASTER_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) + +struct keystore_module { + /** + * Common methods of the keystore module. This *must* be the first member of keystore_module as + * users of this structure will cast a hw_module_t to keystore_module pointer in contexts where + * it's known the hw_module_t references a keystore_module. + */ + hw_module_t common; + + /* There are no keystore module methods other than the common ones. */ +}; + +/** + * Flags for keymaster0_device::flags + */ +enum { + /* + * Indicates this keymaster implementation does not have hardware that + * keeps private keys out of user space. + * + * This should not be implemented on anything other than the default + * implementation. + */ + KEYMASTER_SOFTWARE_ONLY = 1 << 0, + + /* + * This indicates that the key blobs returned via all the primitives + * are sufficient to operate on their own without the trusted OS + * querying userspace to retrieve some other data. Key blobs of + * this type are normally returned encrypted with a + * Key Encryption Key (KEK). + * + * This is currently used by "vold" to know whether the whole disk + * encryption secret can be unwrapped without having some external + * service started up beforehand since the "/data" partition will + * be unavailable at that point. + */ + KEYMASTER_BLOBS_ARE_STANDALONE = 1 << 1, + + /* + * Indicates that the keymaster module supports DSA keys. + */ + KEYMASTER_SUPPORTS_DSA = 1 << 2, + + /* + * Indicates that the keymaster module supports EC keys. + */ + KEYMASTER_SUPPORTS_EC = 1 << 3, +}; + +/** + * Asymmetric key pair types. + */ +typedef enum { + TYPE_RSA = 1, + TYPE_DSA = 2, + TYPE_EC = 3, +} keymaster_keypair_t; + +/** + * Parameters needed to generate an RSA key. + */ +typedef struct { + uint32_t modulus_size; + uint64_t public_exponent; +} keymaster_rsa_keygen_params_t; + +/** + * Parameters needed to generate a DSA key. + */ +typedef struct { + uint32_t key_size; + uint32_t generator_len; + uint32_t prime_p_len; + uint32_t prime_q_len; + const uint8_t* generator; + const uint8_t* prime_p; + const uint8_t* prime_q; +} keymaster_dsa_keygen_params_t; + +/** + * Parameters needed to generate an EC key. + * + * Field size is the only parameter in version 2. The sizes correspond to these required curves: + * + * 192 = NIST P-192 + * 224 = NIST P-224 + * 256 = NIST P-256 + * 384 = NIST P-384 + * 521 = NIST P-521 + * + * The parameters for these curves are available at: http://www.nsa.gov/ia/_files/nist-routines.pdf + * in Chapter 4. + */ +typedef struct { + uint32_t field_size; +} keymaster_ec_keygen_params_t; + + +/** + * Digest type. + */ +typedef enum { + DIGEST_NONE, +} keymaster_digest_algorithm_t; + +/** + * Type of padding used for RSA operations. + */ +typedef enum { + PADDING_NONE, +} keymaster_rsa_padding_t; + + +typedef struct { + keymaster_digest_algorithm_t digest_type; +} keymaster_dsa_sign_params_t; + +typedef struct { + keymaster_digest_algorithm_t digest_type; +} keymaster_ec_sign_params_t; + +typedef struct { + keymaster_digest_algorithm_t digest_type; + keymaster_rsa_padding_t padding_type; +} keymaster_rsa_sign_params_t; + +__END_DECLS + +#endif // ANDROID_HARDWARE_KEYMASTER_COMMON_H diff --git a/third_party/android_hardware_libhardware/include/hardware/keymaster_defs.h b/third_party/android_hardware_libhardware/include/hardware/keymaster_defs.h new file mode 100644 index 00000000000000..1a723c94a8ce36 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/keymaster_defs.h @@ -0,0 +1,539 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_HARDWARE_KEYMASTER_DEFS_H +#define ANDROID_HARDWARE_KEYMASTER_DEFS_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/** + * Authorization tags each have an associated type. This enumeration facilitates tagging each with + * a type, by using the high four bits (of an implied 32-bit unsigned enum value) to specify up to + * 16 data types. These values are ORed with tag IDs to generate the final tag ID values. + */ +typedef enum { + KM_INVALID = 0 << 28, /* Invalid type, used to designate a tag as uninitialized */ + KM_ENUM = 1 << 28, + KM_ENUM_REP = 2 << 28, /* Repeatable enumeration value. */ + KM_UINT = 3 << 28, + KM_UINT_REP = 4 << 28, /* Repeatable integer value */ + KM_ULONG = 5 << 28, + KM_DATE = 6 << 28, + KM_BOOL = 7 << 28, + KM_BIGNUM = 8 << 28, + KM_BYTES = 9 << 28, + KM_ULONG_REP = 10 << 28, /* Repeatable long value */ +} keymaster_tag_type_t; + +typedef enum { + KM_TAG_INVALID = KM_INVALID | 0, + + /* + * Tags that must be semantically enforced by hardware and software implementations. + */ + + /* Crypto parameters */ + KM_TAG_PURPOSE = KM_ENUM_REP | 1, /* keymaster_purpose_t. */ + KM_TAG_ALGORITHM = KM_ENUM | 2, /* keymaster_algorithm_t. */ + KM_TAG_KEY_SIZE = KM_UINT | 3, /* Key size in bits. */ + KM_TAG_BLOCK_MODE = KM_ENUM_REP | 4, /* keymaster_block_mode_t. */ + KM_TAG_DIGEST = KM_ENUM_REP | 5, /* keymaster_digest_t. */ + KM_TAG_PADDING = KM_ENUM_REP | 6, /* keymaster_padding_t. */ + KM_TAG_CALLER_NONCE = KM_BOOL | 7, /* Allow caller to specify nonce or IV. */ + KM_TAG_MIN_MAC_LENGTH = KM_UINT | 8, /* Minimum length of MAC or AEAD authentication tag in + * bits. */ + + /* Algorithm-specific. */ + KM_TAG_RSA_PUBLIC_EXPONENT = KM_ULONG | 200, + + /* Other hardware-enforced. */ + KM_TAG_BLOB_USAGE_REQUIREMENTS = KM_ENUM | 301, /* keymaster_key_blob_usage_requirements_t */ + KM_TAG_BOOTLOADER_ONLY = KM_BOOL | 302, /* Usable only by bootloader */ + + /* + * Tags that should be semantically enforced by hardware if possible and will otherwise be + * enforced by software (keystore). + */ + + /* Key validity period */ + KM_TAG_ACTIVE_DATETIME = KM_DATE | 400, /* Start of validity */ + KM_TAG_ORIGINATION_EXPIRE_DATETIME = KM_DATE | 401, /* Date when new "messages" should no + longer be created. */ + KM_TAG_USAGE_EXPIRE_DATETIME = KM_DATE | 402, /* Date when existing "messages" should no + longer be trusted. */ + KM_TAG_MIN_SECONDS_BETWEEN_OPS = KM_UINT | 403, /* Minimum elapsed time between + cryptographic operations with the key. */ + KM_TAG_MAX_USES_PER_BOOT = KM_UINT | 404, /* Number of times the key can be used per + boot. */ + + /* User authentication */ + KM_TAG_ALL_USERS = KM_BOOL | 500, /* Reserved for future use -- ignore */ + KM_TAG_USER_ID = KM_UINT | 501, /* Reserved for future use -- ignore */ + KM_TAG_USER_SECURE_ID = KM_ULONG_REP | 502, /* Secure ID of authorized user or authenticator(s). + Disallowed if KM_TAG_ALL_USERS or + KM_TAG_NO_AUTH_REQUIRED is present. */ + KM_TAG_NO_AUTH_REQUIRED = KM_BOOL | 503, /* If key is usable without authentication. */ + KM_TAG_USER_AUTH_TYPE = KM_ENUM | 504, /* Bitmask of authenticator types allowed when + * KM_TAG_USER_SECURE_ID contains a secure user ID, + * rather than a secure authenticator ID. Defined in + * hw_authenticator_type_t in hw_auth_token.h. */ + KM_TAG_AUTH_TIMEOUT = KM_UINT | 505, /* Required freshness of user authentication for + private/secret key operations, in seconds. + Public key operations require no authentication. + If absent, authentication is required for every + use. Authentication state is lost when the + device is powered off. */ + + /* Application access control */ + KM_TAG_ALL_APPLICATIONS = KM_BOOL | 600, /* Reserved for future use -- ignore */ + KM_TAG_APPLICATION_ID = KM_BYTES | 601, /* Reserved for fugure use -- ignore */ + + /* + * Semantically unenforceable tags, either because they have no specific meaning or because + * they're informational only. + */ + KM_TAG_APPLICATION_DATA = KM_BYTES | 700, /* Data provided by authorized application. */ + KM_TAG_CREATION_DATETIME = KM_DATE | 701, /* Key creation time */ + KM_TAG_ORIGIN = KM_ENUM | 702, /* keymaster_key_origin_t. */ + KM_TAG_ROLLBACK_RESISTANT = KM_BOOL | 703, /* Whether key is rollback-resistant. */ + KM_TAG_ROOT_OF_TRUST = KM_BYTES | 704, /* Root of trust ID. */ + + /* Tags used only to provide data to or receive data from operations */ + KM_TAG_ASSOCIATED_DATA = KM_BYTES | 1000, /* Used to provide associated data for AEAD modes. */ + KM_TAG_NONCE = KM_BYTES | 1001, /* Nonce or Initialization Vector */ + KM_TAG_AUTH_TOKEN = KM_BYTES | 1002, /* Authentication token that proves secure user + authentication has been performed. Structure + defined in hw_auth_token_t in hw_auth_token.h. */ + KM_TAG_MAC_LENGTH = KM_UINT | 1003, /* MAC or AEAD authentication tag length in bits. */ + + /* Tags used only for SOTER */ + /* Tags used only to check if the key is for SOTER */ + KM_TAG_SOTER_IS_FROM_SOTER = KM_BOOL | 11000, + /* Attach signature signed with ATTK[pri] while exporting public key */ + KM_TAG_SOTER_IS_AUTO_SIGNED_WITH_ATTK_WHEN_GET_PUBLIC_KEY = KM_BOOL | 11001, + /* Attach signature signed with specified private key while exporting public key */ + KM_TAG_SOTER_IS_AUTO_SIGNED_WITH_COMMON_KEY_WHEN_GET_PUBLIC_KEY = KM_BOOL | 11002, + /* keyalias for the keypair of KM_TAG_SOTER_IS_AUTO_SIGNED_WITH_COMMON_KEY_WHEN_GET_PUBLIC_KEY */ + KM_TAG_SOTER_AUTO_SIGNED_COMMON_KEY_WHEN_GET_PUBLIC_KEY = KM_BYTES | 11003, + /* Attach counter while exporting publick key */ + KM_TAG_SOTER_AUTO_ADD_COUNTER_WHEN_GET_PUBLIC_KEY = KM_BOOL | 11004, + /* Attach secmsg(TEE_Name, TEE_Version, Fingerprint_Sensor_Name, Fingerprint_Sensor_Version) + fingerprint_id and counter while signing */ + KM_TAG_SOTER_IS_SECMSG_FID_COUNTER_SIGNED_WHEN_SIGN = KM_BOOL | 11005, + /* use and set ATTK index to next backup ATTK */ + KM_TAG_SOTER_USE_NEXT_ATTK = KM_BOOL | 11006, + /* attach soter uid */ + KM_TAG_SOTER_UID = KM_UINT | 11007, + /* attach key blob of KM_TAG_SOTER_AUTO_SIGNED_COMMON_KEY_WHEN_GET_PUBLIC_KEY if needed */ + KM_TAG_SOTER_AUTO_SIGNED_COMMON_KEY_WHEN_GET_PUBLIC_KEY_BLOB = KM_BYTES | 11008, +} keymaster_tag_t; + +/** + * Algorithms that may be provided by keymaster implementations. Those that must be provided by all + * implementations are tagged as "required". + */ +typedef enum { + /* Asymmetric algorithms. */ + KM_ALGORITHM_RSA = 1, + // KM_ALGORITHM_DSA = 2, -- Removed, do not re-use value 2. + KM_ALGORITHM_EC = 3, + + /* Block ciphers algorithms */ + KM_ALGORITHM_AES = 32, + + /* MAC algorithms */ + KM_ALGORITHM_HMAC = 128, +} keymaster_algorithm_t; + +/** + * Symmetric block cipher modes provided by keymaster implementations. + */ +typedef enum { + /* Unauthenticated modes, usable only for encryption/decryption and not generally recommended + * except for compatibility with existing other protocols. */ + KM_MODE_ECB = 1, + KM_MODE_CBC = 2, + KM_MODE_CTR = 3, + + /* Authenticated modes, usable for encryption/decryption and signing/verification. Recommended + * over unauthenticated modes for all purposes. */ + KM_MODE_GCM = 32, +} keymaster_block_mode_t; + +/** + * Padding modes that may be applied to plaintext for encryption operations. This list includes + * padding modes for both symmetric and asymmetric algorithms. Note that implementations should not + * provide all possible combinations of algorithm and padding, only the + * cryptographically-appropriate pairs. + */ +typedef enum { + KM_PAD_NONE = 1, /* deprecated */ + KM_PAD_RSA_OAEP = 2, + KM_PAD_RSA_PSS = 3, + KM_PAD_RSA_PKCS1_1_5_ENCRYPT = 4, + KM_PAD_RSA_PKCS1_1_5_SIGN = 5, + KM_PAD_PKCS7 = 64, +} keymaster_padding_t; + +/** + * Digests provided by keymaster implementations. + */ +typedef enum { + KM_DIGEST_NONE = 0, + KM_DIGEST_MD5 = 1, /* Optional, may not be implemented in hardware, will be handled in software + * if needed. */ + KM_DIGEST_SHA1 = 2, + KM_DIGEST_SHA_2_224 = 3, + KM_DIGEST_SHA_2_256 = 4, + KM_DIGEST_SHA_2_384 = 5, + KM_DIGEST_SHA_2_512 = 6, +} keymaster_digest_t; + +/** + * The origin of a key (or pair), i.e. where it was generated. Note that KM_TAG_ORIGIN can be found + * in either the hardware-enforced or software-enforced list for a key, indicating whether the key + * is hardware or software-based. Specifically, a key with KM_ORIGIN_GENERATED in the + * hardware-enforced list is guaranteed never to have existed outide the secure hardware. + */ +typedef enum { + KM_ORIGIN_GENERATED = 0, /* Generated in keymaster */ + KM_ORIGIN_IMPORTED = 2, /* Imported, origin unknown */ + KM_ORIGIN_UNKNOWN = 3, /* Keymaster did not record origin. This value can only be seen on + * keys in a keymaster0 implementation. The keymaster0 adapter uses + * this value to document the fact that it is unkown whether the key + * was generated inside or imported into keymaster. */ +} keymaster_key_origin_t; + +/** + * Usability requirements of key blobs. This defines what system functionality must be available + * for the key to function. For example, key "blobs" which are actually handles referencing + * encrypted key material stored in the file system cannot be used until the file system is + * available, and should have BLOB_REQUIRES_FILE_SYSTEM. Other requirements entries will be added + * as needed for implementations. This type is new in 0_4. + */ +typedef enum { + KM_BLOB_STANDALONE = 0, + KM_BLOB_REQUIRES_FILE_SYSTEM = 1, +} keymaster_key_blob_usage_requirements_t; + +/** + * Possible purposes of a key (or pair). This type is new in 0_4. + */ +typedef enum { + KM_PURPOSE_ENCRYPT = 0, + KM_PURPOSE_DECRYPT = 1, + KM_PURPOSE_SIGN = 2, + KM_PURPOSE_VERIFY = 3, +} keymaster_purpose_t; + +typedef struct { + const uint8_t* data; + size_t data_length; +} keymaster_blob_t; + +typedef struct { + keymaster_tag_t tag; + union { + uint32_t enumerated; /* KM_ENUM and KM_ENUM_REP */ + bool boolean; /* KM_BOOL */ + uint32_t integer; /* KM_INT and KM_INT_REP */ + uint64_t long_integer; /* KM_LONG */ + uint64_t date_time; /* KM_DATE */ + keymaster_blob_t blob; /* KM_BIGNUM and KM_BYTES*/ + }; +} keymaster_key_param_t; + +typedef struct { + keymaster_key_param_t* params; /* may be NULL if length == 0 */ + size_t length; +} keymaster_key_param_set_t; + +/** + * Parameters that define a key's characteristics, including authorized modes of usage and access + * control restrictions. The parameters are divided into two categories, those that are enforced by + * secure hardware, and those that are not. For a software-only keymaster implementation the + * enforced array must NULL. Hardware implementations must enforce everything in the enforced + * array. + */ +typedef struct { + keymaster_key_param_set_t hw_enforced; + keymaster_key_param_set_t sw_enforced; +} keymaster_key_characteristics_t; + +typedef struct { + const uint8_t* key_material; + size_t key_material_size; +} keymaster_key_blob_t; + +/** + * Formats for key import and export. At present, only asymmetric key import/export is supported. + * In the future this list will expand greatly to accommodate asymmetric key import/export. + */ +typedef enum { + KM_KEY_FORMAT_X509 = 0, /* for public key export */ + KM_KEY_FORMAT_PKCS8 = 1, /* for asymmetric key pair import */ + KM_KEY_FORMAT_RAW = 3, /* for symmetric key import */ +} keymaster_key_format_t; + +/** + * The keymaster operation API consists of begin, update, finish and abort. This is the type of the + * handle used to tie the sequence of calls together. A 64-bit value is used because it's important + * that handles not be predictable. Implementations must use strong random numbers for handle + * values. + */ +typedef uint64_t keymaster_operation_handle_t; + +typedef enum { + KM_ERROR_OK = 0, + KM_ERROR_ROOT_OF_TRUST_ALREADY_SET = -1, + KM_ERROR_UNSUPPORTED_PURPOSE = -2, + KM_ERROR_INCOMPATIBLE_PURPOSE = -3, + KM_ERROR_UNSUPPORTED_ALGORITHM = -4, + KM_ERROR_INCOMPATIBLE_ALGORITHM = -5, + KM_ERROR_UNSUPPORTED_KEY_SIZE = -6, + KM_ERROR_UNSUPPORTED_BLOCK_MODE = -7, + KM_ERROR_INCOMPATIBLE_BLOCK_MODE = -8, + KM_ERROR_UNSUPPORTED_MAC_LENGTH = -9, + KM_ERROR_UNSUPPORTED_PADDING_MODE = -10, + KM_ERROR_INCOMPATIBLE_PADDING_MODE = -11, + KM_ERROR_UNSUPPORTED_DIGEST = -12, + KM_ERROR_INCOMPATIBLE_DIGEST = -13, + KM_ERROR_INVALID_EXPIRATION_TIME = -14, + KM_ERROR_INVALID_USER_ID = -15, + KM_ERROR_INVALID_AUTHORIZATION_TIMEOUT = -16, + KM_ERROR_UNSUPPORTED_KEY_FORMAT = -17, + KM_ERROR_INCOMPATIBLE_KEY_FORMAT = -18, + KM_ERROR_UNSUPPORTED_KEY_ENCRYPTION_ALGORITHM = -19, /* For PKCS8 & PKCS12 */ + KM_ERROR_UNSUPPORTED_KEY_VERIFICATION_ALGORITHM = -20, /* For PKCS8 & PKCS12 */ + KM_ERROR_INVALID_INPUT_LENGTH = -21, + KM_ERROR_KEY_EXPORT_OPTIONS_INVALID = -22, + KM_ERROR_DELEGATION_NOT_ALLOWED = -23, + KM_ERROR_KEY_NOT_YET_VALID = -24, + KM_ERROR_KEY_EXPIRED = -25, + KM_ERROR_KEY_USER_NOT_AUTHENTICATED = -26, + KM_ERROR_OUTPUT_PARAMETER_NULL = -27, + KM_ERROR_INVALID_OPERATION_HANDLE = -28, + KM_ERROR_INSUFFICIENT_BUFFER_SPACE = -29, + KM_ERROR_VERIFICATION_FAILED = -30, + KM_ERROR_TOO_MANY_OPERATIONS = -31, + KM_ERROR_UNEXPECTED_NULL_POINTER = -32, + KM_ERROR_INVALID_KEY_BLOB = -33, + KM_ERROR_IMPORTED_KEY_NOT_ENCRYPTED = -34, + KM_ERROR_IMPORTED_KEY_DECRYPTION_FAILED = -35, + KM_ERROR_IMPORTED_KEY_NOT_SIGNED = -36, + KM_ERROR_IMPORTED_KEY_VERIFICATION_FAILED = -37, + KM_ERROR_INVALID_ARGUMENT = -38, + KM_ERROR_UNSUPPORTED_TAG = -39, + KM_ERROR_INVALID_TAG = -40, + KM_ERROR_MEMORY_ALLOCATION_FAILED = -41, + KM_ERROR_IMPORT_PARAMETER_MISMATCH = -44, + KM_ERROR_SECURE_HW_ACCESS_DENIED = -45, + KM_ERROR_OPERATION_CANCELLED = -46, + KM_ERROR_CONCURRENT_ACCESS_CONFLICT = -47, + KM_ERROR_SECURE_HW_BUSY = -48, + KM_ERROR_SECURE_HW_COMMUNICATION_FAILED = -49, + KM_ERROR_UNSUPPORTED_EC_FIELD = -50, + KM_ERROR_MISSING_NONCE = -51, + KM_ERROR_INVALID_NONCE = -52, + KM_ERROR_MISSING_MAC_LENGTH = -53, + KM_ERROR_KEY_RATE_LIMIT_EXCEEDED = -54, + KM_ERROR_CALLER_NONCE_PROHIBITED = -55, + KM_ERROR_KEY_MAX_OPS_EXCEEDED = -56, + KM_ERROR_INVALID_MAC_LENGTH = -57, + KM_ERROR_MISSING_MIN_MAC_LENGTH = -58, + KM_ERROR_UNSUPPORTED_MIN_MAC_LENGTH = -59, + + KM_ERROR_UNIMPLEMENTED = -100, + KM_ERROR_VERSION_MISMATCH = -101, + + /* Additional error codes may be added by implementations, but implementers should coordinate + * with Google to avoid code collision. */ + KM_ERROR_UNKNOWN_ERROR = -1000, +} keymaster_error_t; + +/* Convenience functions for manipulating keymaster tag types */ + +static inline keymaster_tag_type_t keymaster_tag_get_type(keymaster_tag_t tag) { + return (keymaster_tag_type_t)(tag & (0xF << 28)); +} + +static inline uint32_t keymaster_tag_mask_type(keymaster_tag_t tag) { + return tag & 0x0FFFFFFF; +} + +static inline bool keymaster_tag_type_repeatable(keymaster_tag_type_t type) { + switch (type) { + case KM_UINT_REP: + case KM_ENUM_REP: + return true; + default: + return false; + } +} + +static inline bool keymaster_tag_repeatable(keymaster_tag_t tag) { + return keymaster_tag_type_repeatable(keymaster_tag_get_type(tag)); +} + +/* Convenience functions for manipulating keymaster_key_param_t structs */ + +inline keymaster_key_param_t keymaster_param_enum(keymaster_tag_t tag, uint32_t value) { + // assert(keymaster_tag_get_type(tag) == KM_ENUM || keymaster_tag_get_type(tag) == KM_ENUM_REP); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.enumerated = value; + return param; +} + +inline keymaster_key_param_t keymaster_param_int(keymaster_tag_t tag, uint32_t value) { + // assert(keymaster_tag_get_type(tag) == KM_INT || keymaster_tag_get_type(tag) == KM_INT_REP); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.integer = value; + return param; +} + +inline keymaster_key_param_t keymaster_param_long(keymaster_tag_t tag, uint64_t value) { + // assert(keymaster_tag_get_type(tag) == KM_LONG); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.long_integer = value; + return param; +} + +inline keymaster_key_param_t keymaster_param_blob(keymaster_tag_t tag, const uint8_t* bytes, + size_t bytes_len) { + // assert(keymaster_tag_get_type(tag) == KM_BYTES || keymaster_tag_get_type(tag) == KM_BIGNUM); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.blob.data = (uint8_t*)bytes; + param.blob.data_length = bytes_len; + return param; +} + +inline keymaster_key_param_t keymaster_param_bool(keymaster_tag_t tag) { + // assert(keymaster_tag_get_type(tag) == KM_BOOL); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.boolean = true; + return param; +} + +inline keymaster_key_param_t keymaster_param_date(keymaster_tag_t tag, uint64_t value) { + // assert(keymaster_tag_get_type(tag) == KM_DATE); + keymaster_key_param_t param; + memset(¶m, 0, sizeof(param)); + param.tag = tag; + param.date_time = value; + return param; +} + +#define KEYMASTER_SIMPLE_COMPARE(a, b) (a < b) ? -1 : ((a > b) ? 1 : 0) +inline int keymaster_param_compare(const keymaster_key_param_t* a, const keymaster_key_param_t* b) { + int retval = KEYMASTER_SIMPLE_COMPARE(a->tag, b->tag); + if (retval != 0) + return retval; + + switch (keymaster_tag_get_type(a->tag)) { + case KM_INVALID: + case KM_BOOL: + return 0; + case KM_ENUM: + case KM_ENUM_REP: + return KEYMASTER_SIMPLE_COMPARE(a->enumerated, b->enumerated); + case KM_UINT: + case KM_UINT_REP: + return KEYMASTER_SIMPLE_COMPARE(a->integer, b->integer); + case KM_ULONG: + case KM_ULONG_REP: + return KEYMASTER_SIMPLE_COMPARE(a->long_integer, b->long_integer); + case KM_DATE: + return KEYMASTER_SIMPLE_COMPARE(a->date_time, b->date_time); + case KM_BIGNUM: + case KM_BYTES: + // Handle the empty cases. + if (a->blob.data_length != 0 && b->blob.data_length == 0) + return -1; + if (a->blob.data_length == 0 && b->blob.data_length == 0) + return 0; + if (a->blob.data_length == 0 && b->blob.data_length > 0) + return 1; + + retval = memcmp(a->blob.data, b->blob.data, a->blob.data_length < b->blob.data_length + ? a->blob.data_length + : b->blob.data_length); + if (retval != 0) + return retval; + else if (a->blob.data_length != b->blob.data_length) { + // Equal up to the common length; longer one is larger. + if (a->blob.data_length < b->blob.data_length) + return -1; + if (a->blob.data_length > b->blob.data_length) + return 1; + }; + } + + return 0; +} +#undef KEYMASTER_SIMPLE_COMPARE + +inline void keymaster_free_param_values(keymaster_key_param_t* param, size_t param_count) { + while (param_count-- > 0) { + switch (keymaster_tag_get_type(param->tag)) { + case KM_BIGNUM: + case KM_BYTES: + free((void*)param->blob.data); + param->blob.data = NULL; + break; + default: + // NOP + break; + } + ++param; + } +} + +inline void keymaster_free_param_set(keymaster_key_param_set_t* set) { + if (set) { + keymaster_free_param_values(set->params, set->length); + free(set->params); + set->params = NULL; + } +} + +inline void keymaster_free_characteristics(keymaster_key_characteristics_t* characteristics) { + if (characteristics) { + keymaster_free_param_set(&characteristics->hw_enforced); + keymaster_free_param_set(&characteristics->sw_enforced); + } +} + +#ifdef __cplusplus +} // extern "C" +#endif // __cplusplus + +#endif // ANDROID_HARDWARE_KEYMASTER_DEFS_H diff --git a/third_party/android_hardware_libhardware/include/hardware/lights.h b/third_party/android_hardware_libhardware/include/hardware/lights.h new file mode 100644 index 00000000000000..777c91593f0d09 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/lights.h @@ -0,0 +1,157 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_LIGHTS_INTERFACE_H +#define ANDROID_LIGHTS_INTERFACE_H + +#include +#include +#include + +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define LIGHTS_HARDWARE_MODULE_ID "lights" + +/* + * These light IDs correspond to logical lights, not physical. + * So for example, if your INDICATOR light is in line with your + * BUTTONS, it might make sense to also light the INDICATOR + * light to a reasonable color when the BUTTONS are lit. + */ +#define LIGHT_ID_BACKLIGHT "backlight" +#define LIGHT_ID_KEYBOARD "keyboard" +#define LIGHT_ID_BUTTONS "buttons" +#define LIGHT_ID_BATTERY "battery" +#define LIGHT_ID_NOTIFICATIONS "notifications" +#define LIGHT_ID_ATTENTION "attention" + +/* + * These lights aren't currently supported by the higher + * layers, but could be someday, so we have the constants + * here now. + */ +#define LIGHT_ID_BLUETOOTH "bluetooth" +#define LIGHT_ID_WIFI "wifi" + +/* + * Additional hardware-specific lights + */ +#define LIGHT_ID_CAPS "caps" +#define LIGHT_ID_FUNC "func" + +/* ************************************************************************ + * Flash modes for the flashMode field of light_state_t. + */ + +#define LIGHT_FLASH_NONE 0 + +/** + * To flash the light at a given rate, set flashMode to LIGHT_FLASH_TIMED, + * and then flashOnMS should be set to the number of milliseconds to turn + * the light on, followed by the number of milliseconds to turn the light + * off. + */ +#define LIGHT_FLASH_TIMED 1 + +/** + * To flash the light using hardware assist, set flashMode to + * the hardware mode. + */ +#define LIGHT_FLASH_HARDWARE 2 + +/** + * Light brightness is managed by a user setting. + */ +#define BRIGHTNESS_MODE_USER 0 + +/** + * Light brightness is managed by a light sensor. + */ +#define BRIGHTNESS_MODE_SENSOR 1 + +/** + * Light mode allows multiple LEDs + */ +#define LIGHT_MODE_MULTIPLE_LEDS 0x01 + +/** + * The parameters that can be set for a given light. + * + * Not all lights must support all parameters. If you + * can do something backward-compatible, you should. + */ +struct light_state_t { + /** + * The color of the LED in ARGB. + * + * Do your best here. + * - If your light can only do red or green, if they ask for blue, + * you should do green. + * - If you can only do a brightness ramp, then use this formula: + * unsigned char brightness = ((77*((color>>16)&0x00ff)) + * + (150*((color>>8)&0x00ff)) + (29*(color&0x00ff))) >> 8; + * - If you can only do on or off, 0 is off, anything else is on. + * + * The high byte should be ignored. Callers will set it to 0xff (which + * would correspond to 255 alpha). + * + * CyanogenMod: The high byte value can be implemented to control the LEDs + * Brightness from the Lights settings. The value goes from 0x01 to 0xFF. + */ + unsigned int color; + + /** + * See the LIGHT_FLASH_* constants + */ + int flashMode; + int flashOnMS; + int flashOffMS; + + /** + * Policy used by the framework to manage the light's brightness. + * Currently the values are BRIGHTNESS_MODE_USER and BRIGHTNESS_MODE_SENSOR. + */ + int brightnessMode; + + /** + * Define the LEDs modes (multiple, ...). + * See the LIGHTS_MODE_* mask constants. + */ + unsigned int ledsModes; +}; + +struct light_device_t { + struct hw_device_t common; + + /** + * Set the provided lights to the provided values. + * + * Returns: 0 on succes, error code on failure. + */ + int (*set_light)(struct light_device_t* dev, + struct light_state_t const* state); +}; + + +__END_DECLS + +#endif // ANDROID_LIGHTS_INTERFACE_H + diff --git a/third_party/android_hardware_libhardware/include/hardware/local_time_hal.h b/third_party/android_hardware_libhardware/include/hardware/local_time_hal.h new file mode 100644 index 00000000000000..946e799783ce57 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/local_time_hal.h @@ -0,0 +1,123 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + +#ifndef ANDROID_LOCAL_TIME_HAL_INTERFACE_H +#define ANDROID_LOCAL_TIME_HAL_INTERFACE_H + +#include + +#include + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define LOCAL_TIME_HARDWARE_MODULE_ID "local_time" + +/** + * Name of the local time devices to open + */ +#define LOCAL_TIME_HARDWARE_INTERFACE "local_time_hw_if" + +/**********************************************************************/ + +/** + * A structure used to collect low level sync data in a lab environment. Most + * HAL implementations will never need this structure. + */ +struct local_time_debug_event { + int64_t local_timesync_event_id; + int64_t local_time; +}; + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +struct local_time_module { + struct hw_module_t common; +}; + +struct local_time_hw_device { + /** + * Common methods of the local time hardware device. This *must* be the first member of + * local_time_hw_device as users of this structure will cast a hw_device_t to + * local_time_hw_device pointer in contexts where it's known the hw_device_t references a + * local_time_hw_device. + */ + struct hw_device_t common; + + /** + * + * Returns the current value of the system wide local time counter + */ + int64_t (*get_local_time)(struct local_time_hw_device* dev); + + /** + * + * Returns the nominal frequency (in hertz) of the system wide local time + * counter + */ + uint64_t (*get_local_freq)(struct local_time_hw_device* dev); + + /** + * + * Sets the HW slew rate of oscillator which drives the system wide local + * time counter. On success, platforms should return 0. Platforms which + * do not support HW slew should leave this method set to NULL. + * + * Valid values for rate range from MIN_INT16 to MAX_INT16. Platform + * implementations should attempt map this range linearly to the min/max + * slew rate of their hardware. + */ + int (*set_local_slew)(struct local_time_hw_device* dev, int16_t rate); + + /** + * + * A method used to collect low level sync data in a lab environments. + * Most HAL implementations will simply set this member to NULL, or return + * -EINVAL to indicate that this functionality is not supported. + * Production HALs should never support this method. + */ + int (*get_debug_log)(struct local_time_hw_device* dev, + struct local_time_debug_event* records, + int max_records); +}; + +typedef struct local_time_hw_device local_time_hw_device_t; + +/** convenience API for opening and closing a supported device */ + +static inline int local_time_hw_device_open( + const struct hw_module_t* module, + struct local_time_hw_device** device) +{ + return module->methods->open(module, LOCAL_TIME_HARDWARE_INTERFACE, + (struct hw_device_t**)device); +} + +static inline int local_time_hw_device_close(struct local_time_hw_device* device) +{ + return device->common.close(&device->common); +} + + +__END_DECLS + +#endif // ANDROID_LOCAL_TIME_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/memtrack.h b/third_party/android_hardware_libhardware/include/hardware/memtrack.h new file mode 100644 index 00000000000000..57ba4ad79661d3 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/memtrack.h @@ -0,0 +1,160 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_MEMTRACK_H +#define ANDROID_INCLUDE_HARDWARE_MEMTRACK_H + +#include +#include +#include + +#include + +__BEGIN_DECLS + +#define MEMTRACK_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) + +/** + * The id of this module + */ +#define MEMTRACK_HARDWARE_MODULE_ID "memtrack" + +/* + * The Memory Tracker HAL is designed to return information about device-specific + * memory usage. The primary goal is to be able to track memory that is not + * trackable in any other way, for example texture memory that is allocated by + * a process, but not mapped in to that process' address space. + * A secondary goal is to be able to categorize memory used by a process into + * GL, graphics, etc. All memory sizes should be in real memory usage, + * accounting for stride, bit depth, rounding up to page size, etc. + * + * A process collecting memory statistics will call getMemory for each + * combination of pid and memory type. For each memory type that it recognizes + * the HAL should fill out an array of memtrack_record structures breaking + * down the statistics of that memory type as much as possible. For example, + * getMemory(, MEMTRACK_TYPE_GL) might return: + * { { 4096, ACCOUNTED | PRIVATE | SYSTEM }, + * { 40960, UNACCOUNTED | PRIVATE | SYSTEM }, + * { 8192, ACCOUNTED | PRIVATE | DEDICATED }, + * { 8192, UNACCOUNTED | PRIVATE | DEDICATED } } + * If the HAL could not differentiate between SYSTEM and DEDICATED memory, it + * could return: + * { { 12288, ACCOUNTED | PRIVATE }, + * { 49152, UNACCOUNTED | PRIVATE } } + * + * Memory should not overlap between types. For example, a graphics buffer + * that has been mapped into the GPU as a surface should show up when + * MEMTRACK_TYPE_GRAPHICS is requested, and not when MEMTRACK_TYPE_GL + * is requested. + */ + +enum memtrack_type { + MEMTRACK_TYPE_OTHER = 0, + MEMTRACK_TYPE_GL = 1, + MEMTRACK_TYPE_GRAPHICS = 2, + MEMTRACK_TYPE_MULTIMEDIA = 3, + MEMTRACK_TYPE_CAMERA = 4, + MEMTRACK_NUM_TYPES, +}; + +struct memtrack_record { + size_t size_in_bytes; + unsigned int flags; +}; + +/** + * Flags to differentiate memory that can already be accounted for in + * /proc//smaps, + * (Shared_Clean + Shared_Dirty + Private_Clean + Private_Dirty = Size). + * In general, memory mapped in to a userspace process is accounted unless + * it was mapped with remap_pfn_range. + * Exactly one of these should be set. + */ +#define MEMTRACK_FLAG_SMAPS_ACCOUNTED (1 << 1) +#define MEMTRACK_FLAG_SMAPS_UNACCOUNTED (1 << 2) + +/** + * Flags to differentiate memory shared across multiple processes vs. memory + * used by a single process. Only zero or one of these may be set in a record. + * If none are set, record is assumed to count shared + private memory. + */ +#define MEMTRACK_FLAG_SHARED (1 << 3) +#define MEMTRACK_FLAG_SHARED_PSS (1 << 4) /* shared / num_procesess */ +#define MEMTRACK_FLAG_PRIVATE (1 << 5) + +/** + * Flags to differentiate memory taken from the kernel's allocation pool vs. + * memory that is dedicated to non-kernel allocations, for example a carveout + * or separate video memory. Only zero or one of these may be set in a record. + * If none are set, record is assumed to count system + dedicated memory. + */ +#define MEMTRACK_FLAG_SYSTEM (1 << 6) +#define MEMTRACK_FLAG_DEDICATED (1 << 7) + +/** + * Flags to differentiate memory accessible by the CPU in non-secure mode vs. + * memory that is protected. Only zero or one of these may be set in a record. + * If none are set, record is assumed to count secure + nonsecure memory. + */ +#define MEMTRACK_FLAG_NONSECURE (1 << 8) +#define MEMTRACK_FLAG_SECURE (1 << 9) + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct memtrack_module { + struct hw_module_t common; + + /** + * (*init)() performs memtrack management setup actions and is called + * once before any calls to getMemory(). + * Returns 0 on success, -errno on error. + */ + int (*init)(const struct memtrack_module *module); + + /** + * (*getMemory)() expects an array of record objects and populates up to + * *num_record structures with the sizes of memory plus associated flags for + * that memory. It also updates *num_records with the total number of + * records it could return if *num_records was large enough when passed in. + * Returning records with size 0 is expected, the number of records should + * not vary between calls to getMemory for the same memory type, even + * for different pids. + * + * The caller will often call getMemory for a type and pid with + * *num_records == 0 to determine how many records to allocate room for, + * this case should be a fast-path in the HAL, returning a constant and + * not querying any kernel files. If *num_records passed in is 0, + * then records may be NULL. + * + * This function must be thread-safe, it may get called from multiple + * threads at the same time. + * + * Returns 0 on success, -ENODEV if the type is not supported, -errno + * on other errors. + */ + int (*getMemory)(const struct memtrack_module *module, + pid_t pid, + int type, + struct memtrack_record *records, + size_t *num_records); +} memtrack_module_t; + +__END_DECLS + +#endif // ANDROID_INCLUDE_HARDWARE_MEMTRACK_H diff --git a/third_party/android_hardware_libhardware/include/hardware/nfc.h b/third_party/android_hardware_libhardware/include/hardware/nfc.h new file mode 100644 index 00000000000000..6002e34e83738f --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/nfc.h @@ -0,0 +1,302 @@ +/* + * Copyright (C) 2011, 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_NFC_HAL_INTERFACE_H +#define ANDROID_NFC_HAL_INTERFACE_H + +#include +#include +#include +#include + +#include + +__BEGIN_DECLS + + +/* NFC device HAL for NCI-based NFC controllers. + * + * This HAL allows NCI silicon vendors to make use + * of the core NCI stack in Android for their own silicon. + * + * The responibilities of the NCI HAL implementation + * are as follows: + * + * - Implement the transport to the NFC controller + * - Implement each of the HAL methods specified below as applicable to their silicon + * - Pass up received NCI messages from the controller to the stack + * + * A simplified timeline of NCI HAL method calls: + * 1) Core NCI stack calls open() + * 2) Core NCI stack executes CORE_RESET and CORE_INIT through calls to write() + * 3) Core NCI stack calls core_initialized() to allow HAL to do post-init configuration + * 4) Core NCI stack calls pre_discover() to allow HAL to prepare for RF discovery + * 5) Core NCI stack starts discovery through calls to write() + * 6) Core NCI stack stops discovery through calls to write() (e.g. screen turns off) + * 7) Core NCI stack calls pre_discover() to prepare for RF discovery (e.g. screen turned back on) + * 8) Core NCI stack starts discovery through calls to write() + * ... + * ... + * 9) Core NCI stack calls close() + */ +#define NFC_NCI_HARDWARE_MODULE_ID "nfc_nci" +#define NFC_NCI_BCM2079X_HARDWARE_MODULE_ID "nfc_nci.bcm2079x" +#define NFC_NCI_NXP_PN54X_HARDWARE_MODULE_ID "nfc_nci.pn54x" +#define NFC_NCI_CONTROLLER "nci" + +/* + * nfc_nci_module_t should contain module-specific parameters + */ +typedef struct nfc_nci_module_t { + /** + * Common methods of the NFC NCI module. This *must* be the first member of + * nfc_nci_module_t as users of this structure will cast a hw_module_t to + * nfc_nci_module_t pointer in contexts where it's known the hw_module_t references a + * nfc_nci_module_t. + */ + struct hw_module_t common; +} nfc_nci_module_t; + +/* + * HAL events that can be passed back to the stack + */ +typedef uint8_t nfc_event_t; + +enum { + HAL_NFC_OPEN_CPLT_EVT = 0x00, + HAL_NFC_CLOSE_CPLT_EVT = 0x01, + HAL_NFC_POST_INIT_CPLT_EVT = 0x02, + HAL_NFC_PRE_DISCOVER_CPLT_EVT = 0x03, + HAL_NFC_REQUEST_CONTROL_EVT = 0x04, + HAL_NFC_RELEASE_CONTROL_EVT = 0x05, + HAL_NFC_ERROR_EVT = 0x06 +}; + +/* + * Allowed status return values for each of the HAL methods + */ +typedef uint8_t nfc_status_t; + +enum { + HAL_NFC_STATUS_OK = 0x00, + HAL_NFC_STATUS_FAILED = 0x01, + HAL_NFC_STATUS_ERR_TRANSPORT = 0x02, + HAL_NFC_STATUS_ERR_CMD_TIMEOUT = 0x03, + HAL_NFC_STATUS_REFUSED = 0x04 +}; + +/* + * The callback passed in from the NFC stack that the HAL + * can use to pass events back to the stack. + */ +typedef void (nfc_stack_callback_t) (nfc_event_t event, nfc_status_t event_status); + +/* + * The callback passed in from the NFC stack that the HAL + * can use to pass incomming data to the stack. + */ +typedef void (nfc_stack_data_callback_t) (uint16_t data_len, uint8_t* p_data); + +/* nfc_nci_device_t starts with a hw_device_t struct, + * followed by device-specific methods and members. + * + * All methods in the NCI HAL are asynchronous. + */ +typedef struct nfc_nci_device { + /** + * Common methods of the NFC NCI device. This *must* be the first member of + * nfc_nci_device_t as users of this structure will cast a hw_device_t to + * nfc_nci_device_t pointer in contexts where it's known the hw_device_t references a + * nfc_nci_device_t. + */ + struct hw_device_t common; + /* + * (*open)() Opens the NFC controller device and performs initialization. + * This may include patch download and other vendor-specific initialization. + * + * If open completes successfully, the controller should be ready to perform + * NCI initialization - ie accept CORE_RESET and subsequent commands through + * the write() call. + * + * If open() returns 0, the NCI stack will wait for a HAL_NFC_OPEN_CPLT_EVT + * before continuing. + * + * If open() returns any other value, the NCI stack will stop. + * + */ + int (*open)(const struct nfc_nci_device *p_dev, nfc_stack_callback_t *p_cback, + nfc_stack_data_callback_t *p_data_cback); + + /* + * (*write)() Performs an NCI write. + * + * This method may queue writes and return immediately. The only + * requirement is that the writes are executed in order. + */ + int (*write)(const struct nfc_nci_device *p_dev, uint16_t data_len, const uint8_t *p_data); + + /* + * (*core_initialized)() is called after the CORE_INIT_RSP is received from the NFCC. + * At this time, the HAL can do any chip-specific configuration. + * + * If core_initialized() returns 0, the NCI stack will wait for a HAL_NFC_POST_INIT_CPLT_EVT + * before continuing. + * + * If core_initialized() returns any other value, the NCI stack will continue + * immediately. + */ + int (*core_initialized)(const struct nfc_nci_device *p_dev, uint8_t* p_core_init_rsp_params); + + /* + * (*pre_discover)() Is called every time before starting RF discovery. + * It is a good place to do vendor-specific configuration that must be + * performed every time RF discovery is about to be started. + * + * If pre_discover() returns 0, the NCI stack will wait for a HAL_NFC_PRE_DISCOVER_CPLT_EVT + * before continuing. + * + * If pre_discover() returns any other value, the NCI stack will start + * RF discovery immediately. + */ + int (*pre_discover)(const struct nfc_nci_device *p_dev); + + /* + * (*close)() Closed the NFC controller. Should free all resources. + */ + int (*close)(const struct nfc_nci_device *p_dev); + + /* + * (*control_granted)() Grant HAL the exclusive control to send NCI commands. + * Called in response to HAL_REQUEST_CONTROL_EVT. + * Must only be called when there are no NCI commands pending. + * HAL_RELEASE_CONTROL_EVT will notify when HAL no longer needs exclusive control. + */ + int (*control_granted)(const struct nfc_nci_device *p_dev); + + /* + * (*power_cycle)() Restart controller by power cyle; + * HAL_OPEN_CPLT_EVT will notify when operation is complete. + */ + int (*power_cycle)(const struct nfc_nci_device *p_dev); +} nfc_nci_device_t; + +/* + * Convenience methods that the NFC stack can use to open + * and close an NCI device + */ +static inline int nfc_nci_open(const struct hw_module_t* module, + nfc_nci_device_t** dev) { + return module->methods->open(module, NFC_NCI_CONTROLLER, + (struct hw_device_t**) dev); +} + +static inline int nfc_nci_close(nfc_nci_device_t* dev) { + return dev->common.close(&dev->common); +} +/* + * End NFC NCI HAL + */ + +/* + * This is a limited NFC HAL for NXP PN544-based devices. + * This HAL as Android is moving to + * an NCI-based NFC stack. + * + * All NCI-based NFC controllers should use the NFC-NCI + * HAL instead. + * Begin PN544 specific HAL + */ +#define NFC_HARDWARE_MODULE_ID "nfc" + +#define NFC_PN544_CONTROLLER "pn544" + +typedef struct nfc_module_t { + /** + * Common methods of the NFC NXP PN544 module. This *must* be the first member of + * nfc_module_t as users of this structure will cast a hw_module_t to + * nfc_module_t pointer in contexts where it's known the hw_module_t references a + * nfc_module_t. + */ + struct hw_module_t common; +} nfc_module_t; + +/* + * PN544 linktypes. + * UART + * I2C + * USB (uses UART DAL) + */ +typedef enum { + PN544_LINK_TYPE_UART, + PN544_LINK_TYPE_I2C, + PN544_LINK_TYPE_USB, + PN544_LINK_TYPE_INVALID, +} nfc_pn544_linktype; + +typedef struct { + /** + * Common methods of the NFC NXP PN544 device. This *must* be the first member of + * nfc_pn544_device_t as users of this structure will cast a hw_device_t to + * nfc_pn544_device_t pointer in contexts where it's known the hw_device_t references a + * nfc_pn544_device_t. + */ + struct hw_device_t common; + + /* The number of EEPROM registers to write */ + uint32_t num_eeprom_settings; + + /* The actual EEPROM settings + * For PN544, each EEPROM setting is a 4-byte entry, + * of the format [0x00, addr_msb, addr_lsb, value]. + */ + uint8_t* eeprom_settings; + + /* The link type to which the PN544 is connected */ + nfc_pn544_linktype linktype; + + /* The device node to which the PN544 is connected */ + const char* device_node; + + /* On Crespo we had an I2C issue that would cause us to sometimes read + * the I2C slave address (0x57) over the bus. libnfc contains + * a hack to ignore this byte and try to read the length byte + * again. + * Set to 0 to disable the workaround, 1 to enable it. + */ + uint8_t enable_i2c_workaround; + /* I2C slave address. Multiple I2C addresses are + * possible for PN544 module. Configure address according to + * board design. + */ + uint8_t i2c_device_address; +} nfc_pn544_device_t; + +static inline int nfc_pn544_open(const struct hw_module_t* module, + nfc_pn544_device_t** dev) { + return module->methods->open(module, NFC_PN544_CONTROLLER, + (struct hw_device_t**) dev); +} + +static inline int nfc_pn544_close(nfc_pn544_device_t* dev) { + return dev->common.close(&dev->common); +} +/* + * End PN544 specific HAL + */ + +__END_DECLS + +#endif // ANDROID_NFC_HAL_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/nfc_tag.h b/third_party/android_hardware_libhardware/include/hardware/nfc_tag.h new file mode 100644 index 00000000000000..040a07d8cb1376 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/nfc_tag.h @@ -0,0 +1,95 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_NFC_TAG_HAL_INTERFACE_H +#define ANDROID_NFC_TAG_HAL_INTERFACE_H + +#include + +#include + +__BEGIN_DECLS + +/* + * HAL for programmable NFC tags. + * + */ + +#define NFC_TAG_HARDWARE_MODULE_ID "nfc_tag" +#define NFC_TAG_ID "tag" + +typedef struct nfc_tag_module_t { + /** + * Common methods of the NFC tag module. This *must* be the first member of + * nfc_tag_module_t as users of this structure will cast a hw_module_t to + * nfc_tag_module_t pointer in contexts where it's known the hw_module_t references a + * nfc_tag_module_t. + */ + struct hw_module_t common; +} nfc_tag_module_t; + +typedef struct nfc_tag_device { + /** + * Common methods of the NFC tag device. This *must* be the first member of + * nfc_tag_device_t as users of this structure will cast a hw_device_t to + * nfc_tag_device_t pointer in contexts where it's known the hw_device_t references a + * nfc_tag_device_t. + */ + struct hw_device_t common; + + /** + * Initialize the NFC tag. + * + * The driver must: + * * Set the static lock bytes to read only + * * Configure the Capability Container to disable write acess + * eg: 0xE1 0x10 0x0F + * + * This function is called once before any calls to setContent(). + * + * Return 0 on success or -errno on error. + */ + int (*init)(const struct nfc_tag_device *dev); + + /** + * Set the NFC tag content. + * + * The driver must write in the data area of the tag starting at + * byte 0 of block 4 and zero the rest of the data area. + * + * Returns 0 on success or -errno on error. + */ + int (*setContent)(const struct nfc_tag_device *dev, const uint8_t *data, size_t len); + + /** + * Returns the memory size of the data area. + */ + int (*getMemorySize)(const struct nfc_tag_device *dev); +} nfc_tag_device_t; + +static inline int nfc_tag_open(const struct hw_module_t* module, + nfc_tag_device_t** dev) { + return module->methods->open(module, NFC_TAG_ID, + (struct hw_device_t**)dev); +} + +static inline int nfc_tag_close(nfc_tag_device_t* dev) { + return dev->common.close(&dev->common); +} + +__END_DECLS + +#endif // ANDROID_NFC_TAG_HAL_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/power.h b/third_party/android_hardware_libhardware/include/hardware/power.h new file mode 100644 index 00000000000000..2eb98fe96610ba --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/power.h @@ -0,0 +1,184 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_POWER_H +#define ANDROID_INCLUDE_HARDWARE_POWER_H + +#include +#include +#include + +#include + +__BEGIN_DECLS + +#define POWER_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) +#define POWER_MODULE_API_VERSION_0_2 HARDWARE_MODULE_API_VERSION(0, 2) +#define POWER_MODULE_API_VERSION_0_3 HARDWARE_MODULE_API_VERSION(0, 3) + +/** + * The id of this module + */ +#define POWER_HARDWARE_MODULE_ID "power" + +/* + * Power hint identifiers passed to (*powerHint) + */ + +typedef enum { + POWER_HINT_VSYNC = 0x00000001, + POWER_HINT_INTERACTION = 0x00000002, + /* DO NOT USE POWER_HINT_VIDEO_ENCODE/_DECODE! They will be removed in + * KLP. + */ + POWER_HINT_VIDEO_ENCODE = 0x00000003, + POWER_HINT_VIDEO_DECODE = 0x00000004, + POWER_HINT_LOW_POWER = 0x00000005, + POWER_HINT_CAM_PREVIEW = 0x00000006, + + POWER_HINT_CPU_BOOST = 0x00000010, + POWER_HINT_LAUNCH_BOOST = 0x00000011, + POWER_HINT_AUDIO = 0x00000020, + POWER_HINT_SET_PROFILE = 0x00000030 + +} power_hint_t; + +typedef enum { + POWER_FEATURE_DOUBLE_TAP_TO_WAKE = 0x00000001, + POWER_FEATURE_SUPPORTED_PROFILES = 0x00001000 +} feature_t; + +/** + * Process info, passed as an opaque handle when + * using POWER_HINT_LAUNCH_BOOST. + */ +typedef struct launch_boost_info { + pid_t pid; + const char* packageName; +} launch_boost_info_t; + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct power_module { + struct hw_module_t common; + + /* + * (*init)() performs power management setup actions at runtime + * startup, such as to set default cpufreq parameters. This is + * called only by the Power HAL instance loaded by + * PowerManagerService. + */ + void (*init)(struct power_module *module); + + /* + * (*setInteractive)() performs power management actions upon the + * system entering interactive state (that is, the system is awake + * and ready for interaction, often with UI devices such as + * display and touchscreen enabled) or non-interactive state (the + * system appears asleep, display usually turned off). The + * non-interactive state is usually entered after a period of + * inactivity, in order to conserve battery power during + * such inactive periods. + * + * Typical actions are to turn on or off devices and adjust + * cpufreq parameters. This function may also call the + * appropriate interfaces to allow the kernel to suspend the + * system to low-power sleep state when entering non-interactive + * state, and to disallow low-power suspend when the system is in + * interactive state. When low-power suspend state is allowed, the + * kernel may suspend the system whenever no wakelocks are held. + * + * on is non-zero when the system is transitioning to an + * interactive / awake state, and zero when transitioning to a + * non-interactive / asleep state. + * + * This function is called to enter non-interactive state after + * turning off the screen (if present), and called to enter + * interactive state prior to turning on the screen. + */ + void (*setInteractive)(struct power_module *module, int on); + + /* + * (*powerHint) is called to pass hints on power requirements, which + * may result in adjustment of power/performance parameters of the + * cpufreq governor and other controls. The possible hints are: + * + * POWER_HINT_VSYNC + * + * Foreground app has started or stopped requesting a VSYNC pulse + * from SurfaceFlinger. If the app has started requesting VSYNC + * then CPU and GPU load is expected soon, and it may be appropriate + * to raise speeds of CPU, memory bus, etc. The data parameter is + * non-zero to indicate VSYNC pulse is now requested, or zero for + * VSYNC pulse no longer requested. + * + * POWER_HINT_INTERACTION + * + * User is interacting with the device, for example, touchscreen + * events are incoming. CPU and GPU load may be expected soon, + * and it may be appropriate to raise speeds of CPU, memory bus, + * etc. The data parameter is the estimated length of the interaction + * in milliseconds, or 0 if unknown. + * + * POWER_HINT_LOW_POWER + * + * Low power mode is activated or deactivated. Low power mode + * is intended to save battery at the cost of performance. The data + * parameter is non-zero when low power mode is activated, and zero + * when deactivated. + * + * POWER_HINT_CPU_BOOST + * + * An operation is happening where it would be ideal for the CPU to + * be boosted for a specific duration. The data parameter is an + * integer value of the boost duration in microseconds. + * + * A particular platform may choose to ignore any hint. + * + * availability: version 0.2 + * + */ + void (*powerHint)(struct power_module *module, power_hint_t hint, + void *data); + + /* + * (*setFeature) is called to turn on or off a particular feature + * depending on the state parameter. The possible features are: + * + * FEATURE_DOUBLE_TAP_TO_WAKE + * + * Enabling/Disabling this feature will allow/disallow the system + * to wake up by tapping the screen twice. + * + * availability: version 0.3 + * + */ + void (*setFeature)(struct power_module *module, feature_t feature, int state); + + /* + * (*getFeature) is called to get the current value of a particular + * feature or capability from the hardware or PowerHAL + */ + int (*getFeature)(struct power_module *module, feature_t feature); + +} power_module_t; + +__END_DECLS + +#endif // ANDROID_INCLUDE_HARDWARE_POWER_H diff --git a/third_party/android_hardware_libhardware/include/hardware/qemu_pipe.h b/third_party/android_hardware_libhardware/include/hardware/qemu_pipe.h new file mode 100644 index 00000000000000..53aec97a083dde --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/qemu_pipe.h @@ -0,0 +1,94 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef ANDROID_INCLUDE_HARDWARE_QEMU_PIPE_H +#define ANDROID_INCLUDE_HARDWARE_QEMU_PIPE_H + +#include +#include +#include +#include +#include /* for pthread_once() */ +#include +#include +#include +#include + +#ifndef D +# define D(...) do{}while(0) +#endif + +/* Try to open a new Qemu fast-pipe. This function returns a file descriptor + * that can be used to communicate with a named service managed by the + * emulator. + * + * This file descriptor can be used as a standard pipe/socket descriptor. + * + * 'pipeName' is the name of the emulator service you want to connect to. + * E.g. 'opengles' or 'camera'. + * + * On success, return a valid file descriptor + * Returns -1 on error, and errno gives the error code, e.g.: + * + * EINVAL -> unknown/unsupported pipeName + * ENOSYS -> fast pipes not available in this system. + * + * ENOSYS should never happen, except if you're trying to run within a + * misconfigured emulator. + * + * You should be able to open several pipes to the same pipe service, + * except for a few special cases (e.g. GSM modem), where EBUSY will be + * returned if more than one client tries to connect to it. + */ +static __inline__ int +qemu_pipe_open(const char* pipeName) +{ + char buff[256]; + int buffLen; + int fd, ret; + + if (pipeName == NULL || pipeName[0] == '\0') { + errno = EINVAL; + return -1; + } + + snprintf(buff, sizeof buff, "pipe:%s", pipeName); + + fd = open("/dev/qemu_pipe", O_RDWR); + if (fd < 0 && errno == ENOENT) + fd = open("/dev/goldfish_pipe", O_RDWR); + if (fd < 0) { + D("%s: Could not open /dev/qemu_pipe: %s", __FUNCTION__, strerror(errno)); + //errno = ENOSYS; + return -1; + } + + buffLen = strlen(buff); + + ret = TEMP_FAILURE_RETRY(write(fd, buff, buffLen+1)); + if (ret != buffLen+1) { + D("%s: Could not connect to %s pipe service: %s", __FUNCTION__, pipeName, strerror(errno)); + if (ret == 0) { + errno = ECONNRESET; + } else if (ret > 0) { + errno = EINVAL; + } + return -1; + } + + return fd; +} + +#endif /* ANDROID_INCLUDE_HARDWARE_QEMUD_PIPE_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/qemud.h b/third_party/android_hardware_libhardware/include/hardware/qemud.h new file mode 100644 index 00000000000000..5c39f9c939b00d --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/qemud.h @@ -0,0 +1,153 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_INCLUDE_HARDWARE_QEMUD_H +#define ANDROID_INCLUDE_HARDWARE_QEMUD_H + +#include +#include "qemu_pipe.h" + +/* the following is helper code that is used by the QEMU-specific + * hardware HAL modules to communicate with the emulator program + * through the 'qemud' multiplexing daemon, or through the qemud + * pipe. + * + * see the documentation comments for details in + * development/emulator/qemud/qemud.c + * + * all definitions here are built into the HAL module to avoid + * having to write a tiny shared library for this. + */ + +/* we expect the D macro to be defined to a function macro + * that sends its formatted string argument(s) to the log. + * If not, ignore the traces. + */ +#ifndef D +# define D(...) ((void)0) +#endif + +static __inline__ int +qemud_fd_write(int fd, const void* buff, int len) +{ + int len2; + do { + len2 = write(fd, buff, len); + } while (len2 < 0 && errno == EINTR); + return len2; +} + +static __inline__ int +qemud_fd_read(int fd, void* buff, int len) +{ + int len2; + do { + len2 = read(fd, buff, len); + } while (len2 < 0 && errno == EINTR); + return len2; +} + +static __inline__ int +qemud_channel_open(const char* name) +{ + int fd; + int namelen = strlen(name); + char answer[2]; + char pipe_name[256]; + + /* First, try to connect to the pipe. */ + snprintf(pipe_name, sizeof(pipe_name), "qemud:%s", name); + fd = qemu_pipe_open(pipe_name); + if (fd < 0) { + D("QEMUD pipe is not available for %s: %s", name, strerror(errno)); + /* If pipe is not available, connect to qemud control socket */ + fd = socket_local_client( "qemud", + ANDROID_SOCKET_NAMESPACE_RESERVED, + SOCK_STREAM ); + if (fd < 0) { + D("no qemud control socket: %s", strerror(errno)); + return -1; + } + + /* send service name to connect */ + if (qemud_fd_write(fd, name, namelen) != namelen) { + D("can't send service name to qemud: %s", + strerror(errno)); + close(fd); + return -1; + } + + /* read answer from daemon */ + if (qemud_fd_read(fd, answer, 2) != 2 || + answer[0] != 'O' || answer[1] != 'K') { + D("cant' connect to %s service through qemud", name); + close(fd); + return -1; + } + } + return fd; +} + +static __inline__ int +qemud_channel_send(int fd, const void* msg, int msglen) +{ + char header[5]; + + if (msglen < 0) + msglen = strlen((const char*)msg); + + if (msglen == 0) + return 0; + + snprintf(header, sizeof header, "%04x", msglen); + if (qemud_fd_write(fd, header, 4) != 4) { + D("can't write qemud frame header: %s", strerror(errno)); + return -1; + } + + if (qemud_fd_write(fd, msg, msglen) != msglen) { + D("can4t write qemud frame payload: %s", strerror(errno)); + return -1; + } + return 0; +} + +static __inline__ int +qemud_channel_recv(int fd, void* msg, int msgsize) +{ + char header[5]; + int size, avail; + + if (qemud_fd_read(fd, header, 4) != 4) { + D("can't read qemud frame header: %s", strerror(errno)); + return -1; + } + header[4] = 0; + if (sscanf(header, "%04x", &size) != 1) { + D("malformed qemud frame header: '%.*s'", 4, header); + return -1; + } + if (size > msgsize) + return -1; + + if (qemud_fd_read(fd, msg, size) != size) { + D("can't read qemud frame payload: %s", strerror(errno)); + return -1; + } + return size; +} + +#endif /* ANDROID_INCLUDE_HARDWARE_QEMUD_H */ diff --git a/third_party/android_hardware_libhardware/include/hardware/radio.h b/third_party/android_hardware_libhardware/include/hardware/radio.h new file mode 100644 index 00000000000000..145deb5737b4ea --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/radio.h @@ -0,0 +1,298 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include + +#ifndef ANDROID_RADIO_HAL_H +#define ANDROID_RADIO_HAL_H + + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define RADIO_HARDWARE_MODULE_ID "radio" + +/** + * Name of the audio devices to open + */ +#define RADIO_HARDWARE_DEVICE "radio_hw_device" + +#define RADIO_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define RADIO_MODULE_API_VERSION_CURRENT RADIO_MODULE_API_VERSION_1_0 + + +#define RADIO_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define RADIO_DEVICE_API_VERSION_CURRENT RADIO_DEVICE_API_VERSION_1_0 + +/** + * List of known radio HAL modules. This is the base name of the radio HAL + * library composed of the "radio." prefix, one of the base names below and + * a suffix specific to the device. + * E.g: radio.fm.default.so + */ + +#define RADIO_HARDWARE_MODULE_ID_FM "fm" /* corresponds to RADIO_CLASS_AM_FM */ +#define RADIO_HARDWARE_MODULE_ID_SAT "sat" /* corresponds to RADIO_CLASS_SAT */ +#define RADIO_HARDWARE_MODULE_ID_DT "dt" /* corresponds to RADIO_CLASS_DT */ + + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +struct radio_module { + struct hw_module_t common; +}; + +/* + * Callback function called by the HAL when one of the following occurs: + * - event RADIO_EVENT_HW_FAILURE: radio chip of driver failure requiring + * closing and reopening of the tuner interface. + * - event RADIO_EVENT_CONFIG: new configuration applied in response to open_tuner(), + * or set_configuration(). The event status is 0 (no error) if the configuration has been applied, + * -EINVAL is not or -ETIMEDOUT in case of time out. + * - event RADIO_EVENT_TUNED: tune locked on new station/frequency following scan(), + * step(), tune() or auto AF switching. The event status is 0 (no error) if in tune, + * -EINVAL is not tuned and data in radio_program_info is not valid or -ETIMEDOUT if scan() + * timed out. + * - event RADIO_EVENT_TA: at the beginning and end of traffic announcement if current + * configuration enables TA. + * - event RADIO_EVENT_AF: after automatic switching to alternate frequency if current + * configuration enables AF switching. + * - event RADIO_EVENT_ANTENNA: when the antenna is connected or disconnected. + * - event RADIO_EVENT_METADATA: when new meta data are received from the tuned station. + * The callback MUST NOT be called synchronously while executing a HAL function but from + * a separate thread. + */ +typedef void (*radio_callback_t)(radio_hal_event_t *event, void *cookie); + +/* control interface for a radio tuner */ +struct radio_tuner { + /* + * Apply current radio band configuration (band, range, channel spacing ...). + * + * arguments: + * - config: the band configuration to apply + * + * returns: + * 0 if configuration could be applied + * -EINVAL if configuration requested is invalid + * + * Automatically cancels pending scan, step or tune. + * + * Callback function with event RADIO_EVENT_CONFIG MUST be called once the + * configuration is applied or a failure occurs or after a time out. + */ + int (*set_configuration)(const struct radio_tuner *tuner, + const radio_hal_band_config_t *config); + + /* + * Retrieve current radio band configuration. + * + * arguments: + * - config: where to return the band configuration + * + * returns: + * 0 if valid configuration is returned + * -EINVAL if invalid arguments are passed + */ + int (*get_configuration)(const struct radio_tuner *tuner, + radio_hal_band_config_t *config); + + /* + * Start scanning up to next valid station. + * Must be called when a valid configuration has been applied. + * + * arguments: + * - direction: RADIO_DIRECTION_UP or RADIO_DIRECTION_DOWN + * - skip_sub_channel: valid for HD radio or digital radios only: ignore sub channels + * (e.g SPS for HD radio). + * + * returns: + * 0 if scan successfully started + * -ENOSYS if called out of sequence + * -ENODEV if another error occurs + * + * Automatically cancels pending scan, step or tune. + * + * Callback function with event RADIO_EVENT_TUNED MUST be called once + * locked on a station or after a time out or full frequency scan if + * no station found. The event status should indicate if a valid station + * is tuned or not. + */ + int (*scan)(const struct radio_tuner *tuner, + radio_direction_t direction, bool skip_sub_channel); + + /* + * Move one channel spacing up or down. + * Must be called when a valid configuration has been applied. + * + * arguments: + * - direction: RADIO_DIRECTION_UP or RADIO_DIRECTION_DOWN + * - skip_sub_channel: valid for HD radio or digital radios only: ignore sub channels + * (e.g SPS for HD radio). + * + * returns: + * 0 if step successfully started + * -ENOSYS if called out of sequence + * -ENODEV if another error occurs + * + * Automatically cancels pending scan, step or tune. + * + * Callback function with event RADIO_EVENT_TUNED MUST be called once + * step completed or after a time out. The event status should indicate + * if a valid station is tuned or not. + */ + int (*step)(const struct radio_tuner *tuner, + radio_direction_t direction, bool skip_sub_channel); + + /* + * Tune to specified frequency. + * Must be called when a valid configuration has been applied. + * + * arguments: + * - channel: channel to tune to. A frequency in kHz for AM/FM/HD Radio bands. + * - sub_channel: valid for HD radio or digital radios only: (e.g SPS number for HD radio). + * + * returns: + * 0 if tune successfully started + * -ENOSYS if called out of sequence + * -EINVAL if invalid arguments are passed + * -ENODEV if another error occurs + * + * Automatically cancels pending scan, step or tune. + * + * Callback function with event RADIO_EVENT_TUNED MUST be called once + * tuned or after a time out. The event status should indicate + * if a valid station is tuned or not. + */ + int (*tune)(const struct radio_tuner *tuner, + unsigned int channel, unsigned int sub_channel); + + /* + * Cancel a scan, step or tune operation. + * Must be called while a scan, step or tune operation is pending + * (callback not yet sent). + * + * returns: + * 0 if successful + * -ENOSYS if called out of sequence + * -ENODEV if another error occurs + * + * The callback is not sent. + */ + int (*cancel)(const struct radio_tuner *tuner); + + /* + * Retrieve current station information. + * + * arguments: + * - info: where to return the program info. + * If info->metadata is NULL. no meta data should be returned. + * If meta data must be returned, they should be added to or cloned to + * info->metadata, not passed from a newly created meta data buffer. + * + * returns: + * 0 if tuned and information available + * -EINVAL if invalid arguments are passed + * -ENODEV if another error occurs + */ + int (*get_program_information)(const struct radio_tuner *tuner, + radio_program_info_t *info); +}; + +struct radio_hw_device { + struct hw_device_t common; + + /* + * Retrieve implementation properties. + * + * arguments: + * - properties: where to return the module properties + * + * returns: + * 0 if no error + * -EINVAL if invalid arguments are passed + */ + int (*get_properties)(const struct radio_hw_device *dev, + radio_hal_properties_t *properties); + + /* + * Open a tuner interface for the requested configuration. + * If no other tuner is opened, this will activate the radio module. + * + * arguments: + * - config: the band configuration to apply + * - audio: this tuner will be used for live radio listening and should be connected to + * the radio audio source. + * - callback: the event callback + * - cookie: the cookie to pass when calling the callback + * - tuner: where to return the tuner interface + * + * returns: + * 0 if HW was powered up and configuration could be applied + * -EINVAL if configuration requested is invalid + * -ENOSYS if called out of sequence + * + * Callback function with event RADIO_EVENT_CONFIG MUST be called once the + * configuration is applied or a failure occurs or after a time out. + */ + int (*open_tuner)(const struct radio_hw_device *dev, + const radio_hal_band_config_t *config, + bool audio, + radio_callback_t callback, + void *cookie, + const struct radio_tuner **tuner); + + /* + * Close a tuner interface. + * If the last tuner is closed, the radio module is deactivated. + * + * arguments: + * - tuner: the tuner interface to close + * + * returns: + * 0 if powered down successfully. + * -EINVAL if an invalid argument is passed + * -ENOSYS if called out of sequence + */ + int (*close_tuner)(const struct radio_hw_device *dev, const struct radio_tuner *tuner); + +}; + +typedef struct radio_hw_device radio_hw_device_t; + +/** convenience API for opening and closing a supported device */ + +static inline int radio_hw_device_open(const struct hw_module_t* module, + struct radio_hw_device** device) +{ + return module->methods->open(module, RADIO_HARDWARE_DEVICE, + (struct hw_device_t**)device); +} + +static inline int radio_hw_device_close(const struct radio_hw_device* device) +{ + return device->common.close((struct hw_device_t *)&device->common); +} + +__END_DECLS + +#endif // ANDROID_RADIO_HAL_H diff --git a/third_party/android_hardware_libhardware/include/hardware/sensors.h b/third_party/android_hardware_libhardware/include/hardware/sensors.h new file mode 100644 index 00000000000000..51bffe1196e6d7 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/sensors.h @@ -0,0 +1,1096 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_SENSORS_INTERFACE_H +#define ANDROID_SENSORS_INTERFACE_H + +#include +#include +#include + +#include +#include + +__BEGIN_DECLS + +/*****************************************************************************/ + +#define SENSORS_HEADER_VERSION 1 +#define SENSORS_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) +#define SENSORS_DEVICE_API_VERSION_0_1 HARDWARE_DEVICE_API_VERSION_2(0, 1, SENSORS_HEADER_VERSION) +#define SENSORS_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION_2(1, 0, SENSORS_HEADER_VERSION) +#define SENSORS_DEVICE_API_VERSION_1_1 HARDWARE_DEVICE_API_VERSION_2(1, 1, SENSORS_HEADER_VERSION) +#define SENSORS_DEVICE_API_VERSION_1_2 HARDWARE_DEVICE_API_VERSION_2(1, 2, SENSORS_HEADER_VERSION) +#define SENSORS_DEVICE_API_VERSION_1_3 HARDWARE_DEVICE_API_VERSION_2(1, 3, SENSORS_HEADER_VERSION) +#define SENSORS_DEVICE_API_VERSION_1_4 HARDWARE_DEVICE_API_VERSION_2(1, 4, SENSORS_HEADER_VERSION) + +/** + * Please see the Sensors section of source.android.com for an + * introduction to and detailed descriptions of Android sensor types: + * http://source.android.com/devices/sensors/index.html + */ + +/** + * The id of this module + */ +#define SENSORS_HARDWARE_MODULE_ID "sensors" + +/** + * Name of the sensors device to open + */ +#define SENSORS_HARDWARE_POLL "poll" + +/** + * Handles must be higher than SENSORS_HANDLE_BASE and must be unique. + * A Handle identifies a given sensors. The handle is used to activate + * and/or deactivate sensors. + * In this version of the API there can only be 256 handles. + */ +#define SENSORS_HANDLE_BASE 0 +#define SENSORS_HANDLE_BITS 8 +#define SENSORS_HANDLE_COUNT (1< 35 degrees + * + * Large accelerations without a change in phone orientation should not trigger a tilt event. + * For example, a sharp turn or strong acceleration while driving a car should not trigger a tilt + * event, even though the angle of the average acceleration might vary by more than 35 degrees. + * + * Typically, this sensor is implemented with the help of only an accelerometer. Other sensors can + * be used as well if they do not increase the power consumption significantly. This is a low power + * sensor that should allow the AP to go into suspend mode. Do not emulate this sensor in the HAL. + * Like other wake up sensors, the driver is expected to a hold a wake_lock with a timeout of 200 ms + * while reporting this event. The only allowed return value is 1.0. + * + * Implement only the wake-up version of this sensor. + */ +#define SENSOR_TYPE_TILT_DETECTOR (22) +#define SENSOR_STRING_TYPE_TILT_DETECTOR "android.sensor.tilt_detector" + +/* + * SENSOR_TYPE_WAKE_GESTURE + * reporting-mode: one-shot + * + * A sensor enabling waking up the device based on a device specific motion. + * + * When this sensor triggers, the device behaves as if the power button was + * pressed, turning the screen on. This behavior (turning on the screen when + * this sensor triggers) might be deactivated by the user in the device + * settings. Changes in settings do not impact the behavior of the sensor: + * only whether the framework turns the screen on when it triggers. + * + * The actual gesture to be detected is not specified, and can be chosen by + * the manufacturer of the device. + * This sensor must be low power, as it is likely to be activated 24/7. + * The only allowed value to return is 1.0. + * + * Implement only the wake-up version of this sensor. + */ +#define SENSOR_TYPE_WAKE_GESTURE (23) +#define SENSOR_STRING_TYPE_WAKE_GESTURE "android.sensor.wake_gesture" + +/* + * SENSOR_TYPE_GLANCE_GESTURE + * reporting-mode: one-shot + * + * A sensor enabling briefly turning the screen on to enable the user to + * glance content on screen based on a specific motion. The device should + * turn the screen off after a few moments. + * + * When this sensor triggers, the device turns the screen on momentarily + * to allow the user to glance notifications or other content while the + * device remains locked in a non-interactive state (dozing). This behavior + * (briefly turning on the screen when this sensor triggers) might be deactivated + * by the user in the device settings. Changes in settings do not impact the + * behavior of the sensor: only whether the framework briefly turns the screen on + * when it triggers. + * + * The actual gesture to be detected is not specified, and can be chosen by + * the manufacturer of the device. + * This sensor must be low power, as it is likely to be activated 24/7. + * The only allowed value to return is 1.0. + * + * Implement only the wake-up version of this sensor. + */ +#define SENSOR_TYPE_GLANCE_GESTURE (24) +#define SENSOR_STRING_TYPE_GLANCE_GESTURE "android.sensor.glance_gesture" + +/** + * SENSOR_TYPE_PICK_UP_GESTURE + * reporting-mode: one-shot + * + * A sensor of this type triggers when the device is picked up regardless of wherever is was + * before (desk, pocket, bag). The only allowed return value is 1.0. + * This sensor de-activates itself immediately after it triggers. + * + * Implement only the wake-up version of this sensor. + */ +#define SENSOR_TYPE_PICK_UP_GESTURE (25) +#define SENSOR_STRING_TYPE_PICK_UP_GESTURE "android.sensor.pick_up_gesture" + +/* + * SENSOR_TYPE_WRIST_TILT_GESTURE + * trigger-mode: special + * wake-up sensor: yes + * + * A sensor of this type triggers an event each time a tilt of the wrist-worn + * device is detected. + * + * This sensor must be low power, as it is likely to be activated 24/7. + * The only allowed value to return is 1.0. + * + * Implement only the wake-up version of this sensor. + */ +#define SENSOR_TYPE_WRIST_TILT_GESTURE (26) +#define SENSOR_STRING_TYPE_WRIST_TILT_GESTURE "android.sensor.wrist_tilt_gesture" + +/** + * Values returned by the accelerometer in various locations in the universe. + * all values are in SI units (m/s^2) + */ +#define GRAVITY_SUN (275.0f) +#define GRAVITY_EARTH (9.80665f) + +/** Maximum magnetic field on Earth's surface */ +#define MAGNETIC_FIELD_EARTH_MAX (60.0f) + +/** Minimum magnetic field on Earth's surface */ +#define MAGNETIC_FIELD_EARTH_MIN (30.0f) + +/** + * Possible values of the status field of sensor events. + */ +#define SENSOR_STATUS_NO_CONTACT -1 +#define SENSOR_STATUS_UNRELIABLE 0 +#define SENSOR_STATUS_ACCURACY_LOW 1 +#define SENSOR_STATUS_ACCURACY_MEDIUM 2 +#define SENSOR_STATUS_ACCURACY_HIGH 3 + +/** + * sensor event data + */ +typedef struct { + union { + float v[3]; + struct { + float x; + float y; + float z; + }; + struct { + float azimuth; + float pitch; + float roll; + }; + }; + int8_t status; + uint8_t reserved[3]; +} sensors_vec_t; + +/** + * uncalibrated gyroscope and magnetometer event data + */ +typedef struct { + union { + float uncalib[3]; + struct { + float x_uncalib; + float y_uncalib; + float z_uncalib; + }; + }; + union { + float bias[3]; + struct { + float x_bias; + float y_bias; + float z_bias; + }; + }; +} uncalibrated_event_t; + +/** + * Meta data event data + */ +typedef struct meta_data_event { + int32_t what; + int32_t sensor; +} meta_data_event_t; + +/** + * Heart rate event data + */ +typedef struct { + // Heart rate in beats per minute. + // Set to 0 when status is SENSOR_STATUS_UNRELIABLE or ..._NO_CONTACT + float bpm; + // Status of the sensor for this reading. Set to one SENSOR_STATUS_... + // Note that this value should only be set for sensors that explicitly define + // the meaning of this field. This field is not piped through the framework + // for other sensors. + int8_t status; +} heart_rate_event_t; + +/** + * Union of the various types of sensor data + * that can be returned. + */ +typedef struct sensors_event_t { + /* must be sizeof(struct sensors_event_t) */ + int32_t version; + + /* sensor identifier */ + int32_t sensor; + + /* sensor type */ + int32_t type; + + /* reserved */ + int32_t reserved0; + + /* time is in nanosecond */ + int64_t timestamp; + + union { + union { + float data[16]; + + /* acceleration values are in meter per second per second (m/s^2) */ + sensors_vec_t acceleration; + + /* magnetic vector values are in micro-Tesla (uT) */ + sensors_vec_t magnetic; + + /* orientation values are in degrees */ + sensors_vec_t orientation; + + /* gyroscope values are in rad/s */ + sensors_vec_t gyro; + + /* temperature is in degrees centigrade (Celsius) */ + float temperature; + + /* distance in centimeters */ + float distance; + + /* light in SI lux units */ + float light; + + /* pressure in hectopascal (hPa) */ + float pressure; + + /* relative humidity in percent */ + float relative_humidity; + + /* uncalibrated gyroscope values are in rad/s */ + uncalibrated_event_t uncalibrated_gyro; + + /* uncalibrated magnetometer values are in micro-Teslas */ + uncalibrated_event_t uncalibrated_magnetic; + + /* heart rate data containing value in bpm and status */ + heart_rate_event_t heart_rate; + + /* this is a special event. see SENSOR_TYPE_META_DATA above. + * sensors_meta_data_event_t events are all reported with a type of + * SENSOR_TYPE_META_DATA. The handle is ignored and must be zero. + */ + meta_data_event_t meta_data; + }; + + union { + uint64_t data[8]; + + /* step-counter */ + uint64_t step_counter; + } u64; + }; + + /* Reserved flags for internal use. Set to zero. */ + uint32_t flags; + + uint32_t reserved1[3]; +} sensors_event_t; + + +/* see SENSOR_TYPE_META_DATA */ +typedef sensors_event_t sensors_meta_data_event_t; + + +struct sensor_t; + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +struct sensors_module_t { + struct hw_module_t common; + + /** + * Enumerate all available sensors. The list is returned in "list". + * @return number of sensors in the list + */ + int (*get_sensors_list)(struct sensors_module_t* module, + struct sensor_t const** list); + + /** + * Place the module in a specific mode. The following modes are defined + * + * 0 - Normal operation. Default state of the module. + * 1 - Loopback mode. Data is injected for the the supported + * sensors by the sensor service in this mode. + * @return 0 on success + * -EINVAL if requested mode is not supported + * -EPERM if operation is not allowed + */ + int (*set_operation_mode)(unsigned int mode); +}; + +struct sensor_t { + + /* Name of this sensor. + * All sensors of the same "type" must have a different "name". + */ + const char* name; + + /* vendor of the hardware part */ + const char* vendor; + + /* version of the hardware part + driver. The value of this field + * must increase when the driver is updated in a way that changes the + * output of this sensor. This is important for fused sensors when the + * fusion algorithm is updated. + */ + int version; + + /* handle that identifies this sensors. This handle is used to reference + * this sensor throughout the HAL API. + */ + int handle; + + /* this sensor's type. */ + int type; + + /* maximum range of this sensor's value in SI units */ + float maxRange; + + /* smallest difference between two values reported by this sensor */ + float resolution; + + /* rough estimate of this sensor's power consumption in mA */ + float power; + + /* this value depends on the reporting mode: + * + * continuous: minimum sample period allowed in microseconds + * on-change : 0 + * one-shot :-1 + * special : 0, unless otherwise noted + */ + int32_t minDelay; + + /* number of events reserved for this sensor in the batch mode FIFO. + * If there is a dedicated FIFO for this sensor, then this is the + * size of this FIFO. If the FIFO is shared with other sensors, + * this is the size reserved for that sensor and it can be zero. + */ + uint32_t fifoReservedEventCount; + + /* maximum number of events of this sensor that could be batched. + * This is especially relevant when the FIFO is shared between + * several sensors; this value is then set to the size of that FIFO. + */ + uint32_t fifoMaxEventCount; + + /* type of this sensor as a string. Set to corresponding + * SENSOR_STRING_TYPE_*. + * When defining an OEM specific sensor or sensor manufacturer specific + * sensor, use your reserve domain name as a prefix. + * ex: com.google.glass.onheaddetector + * For sensors of known type, the android framework might overwrite this + * string automatically. + */ + const char* stringType; + + /* permission required to see this sensor, register to it and receive data. + * Set to "" if no permission is required. Some sensor types like the + * heart rate monitor have a mandatory require_permission. + * For sensors that always require a specific permission, like the heart + * rate monitor, the android framework might overwrite this string + * automatically. + */ + const char* requiredPermission; + + /* This value is defined only for continuous mode and on-change sensors. It is the delay between + * two sensor events corresponding to the lowest frequency that this sensor supports. When lower + * frequencies are requested through batch()/setDelay() the events will be generated at this + * frequency instead. It can be used by the framework or applications to estimate when the batch + * FIFO may be full. + * + * NOTE: 1) period_ns is in nanoseconds where as maxDelay/minDelay are in microseconds. + * continuous, on-change: maximum sampling period allowed in microseconds. + * one-shot, special : 0 + * 2) maxDelay should always fit within a 32 bit signed integer. It is declared as 64 bit + * on 64 bit architectures only for binary compatibility reasons. + * Availability: SENSORS_DEVICE_API_VERSION_1_3 + */ + #ifdef __LP64__ + int64_t maxDelay; + #else + int32_t maxDelay; + #endif + + /* Flags for sensor. See SENSOR_FLAG_* above. Only the least significant 32 bits are used here. + * It is declared as 64 bit on 64 bit architectures only for binary compatibility reasons. + * Availability: SENSORS_DEVICE_API_VERSION_1_3 + */ + #ifdef __LP64__ + uint64_t flags; + #else + uint32_t flags; + #endif + + /* reserved fields, must be zero */ + void* reserved[2]; +}; + + +/* + * sensors_poll_device_t is used with SENSORS_DEVICE_API_VERSION_0_1 + * and is present for backward binary and source compatibility. + * See the Sensors HAL interface section for complete descriptions of the + * following functions: + * http://source.android.com/devices/sensors/index.html#hal + */ +struct sensors_poll_device_t { + struct hw_device_t common; + int (*activate)(struct sensors_poll_device_t *dev, + int sensor_handle, int enabled); + int (*setDelay)(struct sensors_poll_device_t *dev, + int sensor_handle, int64_t sampling_period_ns); + int (*poll)(struct sensors_poll_device_t *dev, + sensors_event_t* data, int count); +}; + +/* + * struct sensors_poll_device_1 is used in HAL versions >= SENSORS_DEVICE_API_VERSION_1_0 + */ +typedef struct sensors_poll_device_1 { + union { + /* sensors_poll_device_1 is compatible with sensors_poll_device_t, + * and can be down-cast to it + */ + struct sensors_poll_device_t v0; + + struct { + struct hw_device_t common; + + /* Activate/de-activate one sensor. Return 0 on success, negative + * + * sensor_handle is the handle of the sensor to change. + * enabled set to 1 to enable, or 0 to disable the sensor. + * + * Return 0 on success, negative errno code otherwise. + */ + int (*activate)(struct sensors_poll_device_t *dev, + int sensor_handle, int enabled); + + /** + * Set the events's period in nanoseconds for a given sensor. + * If sampling_period_ns > max_delay it will be truncated to + * max_delay and if sampling_period_ns < min_delay it will be + * replaced by min_delay. + */ + int (*setDelay)(struct sensors_poll_device_t *dev, + int sensor_handle, int64_t sampling_period_ns); + + /** + * Returns an array of sensor data. + */ + int (*poll)(struct sensors_poll_device_t *dev, + sensors_event_t* data, int count); + }; + }; + + + /* + * Sets a sensor’s parameters, including sampling frequency and maximum + * report latency. This function can be called while the sensor is + * activated, in which case it must not cause any sensor measurements to + * be lost: transitioning from one sampling rate to the other cannot cause + * lost events, nor can transitioning from a high maximum report latency to + * a low maximum report latency. + * See the Batching sensor results page for details: + * http://source.android.com/devices/sensors/batching.html + */ + int (*batch)(struct sensors_poll_device_1* dev, + int sensor_handle, int flags, int64_t sampling_period_ns, + int64_t max_report_latency_ns); + + /* + * Flush adds a META_DATA_FLUSH_COMPLETE event (sensors_event_meta_data_t) + * to the end of the "batch mode" FIFO for the specified sensor and flushes + * the FIFO. + * If the FIFO is empty or if the sensor doesn't support batching (FIFO size zero), + * it should return SUCCESS along with a trivial META_DATA_FLUSH_COMPLETE event added to the + * event stream. This applies to all sensors other than one-shot sensors. + * If the sensor is a one-shot sensor, flush must return -EINVAL and not generate + * any flush complete metadata. + * If the sensor is not active at the time flush() is called, flush() should return + * -EINVAL. + */ + int (*flush)(struct sensors_poll_device_1* dev, int sensor_handle); + + /* + * Inject a single sensor sample to be to this device. + * data points to the sensor event to be injected + * @return 0 on success + * -EPERM if operation is not allowed + * -EINVAL if sensor event cannot be injected + */ + int (*inject_sensor_data)(struct sensors_poll_device_1 *dev, const sensors_event_t *data); + + void (*reserved_procs[7])(void); + +} sensors_poll_device_1_t; + + +/** convenience API for opening and closing a device */ + +static inline int sensors_open(const struct hw_module_t* module, + struct sensors_poll_device_t** device) { + return module->methods->open(module, + SENSORS_HARDWARE_POLL, (struct hw_device_t**)device); +} + +static inline int sensors_close(struct sensors_poll_device_t* device) { + return device->common.close(&device->common); +} + +static inline int sensors_open_1(const struct hw_module_t* module, + sensors_poll_device_1_t** device) { + return module->methods->open(module, + SENSORS_HARDWARE_POLL, (struct hw_device_t**)device); +} + +static inline int sensors_close_1(sensors_poll_device_1_t* device) { + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_SENSORS_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/sound_trigger.h b/third_party/android_hardware_libhardware/include/hardware/sound_trigger.h new file mode 100644 index 00000000000000..2a8db87caae265 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/sound_trigger.h @@ -0,0 +1,130 @@ +/* + * Copyright (C) 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include + +#ifndef ANDROID_SOUND_TRIGGER_HAL_H +#define ANDROID_SOUND_TRIGGER_HAL_H + + +__BEGIN_DECLS + +/** + * The id of this module + */ +#define SOUND_TRIGGER_HARDWARE_MODULE_ID "sound_trigger" + +/** + * Name of the audio devices to open + */ +#define SOUND_TRIGGER_HARDWARE_INTERFACE "sound_trigger_hw_if" + +#define SOUND_TRIGGER_MODULE_API_VERSION_1_0 HARDWARE_MODULE_API_VERSION(1, 0) +#define SOUND_TRIGGER_MODULE_API_VERSION_CURRENT SOUND_TRIGGER_MODULE_API_VERSION_1_0 + + +#define SOUND_TRIGGER_DEVICE_API_VERSION_1_0 HARDWARE_DEVICE_API_VERSION(1, 0) +#define SOUND_TRIGGER_DEVICE_API_VERSION_CURRENT SOUND_TRIGGER_DEVICE_API_VERSION_1_0 + +/** + * List of known sound trigger HAL modules. This is the base name of the sound_trigger HAL + * library composed of the "sound_trigger." prefix, one of the base names below and + * a suffix specific to the device. + * e.g: sondtrigger.primary.goldfish.so or sound_trigger.primary.default.so + */ + +#define SOUND_TRIGGER_HARDWARE_MODULE_ID_PRIMARY "primary" + + +/** + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +struct sound_trigger_module { + struct hw_module_t common; +}; + +typedef void (*recognition_callback_t)(struct sound_trigger_recognition_event *event, void *cookie); +typedef void (*sound_model_callback_t)(struct sound_trigger_model_event *event, void *cookie); + +struct sound_trigger_hw_device { + struct hw_device_t common; + + /* + * Retrieve implementation properties. + */ + int (*get_properties)(const struct sound_trigger_hw_device *dev, + struct sound_trigger_properties *properties); + + /* + * Load a sound model. Once loaded, recognition of this model can be started and stopped. + * Only one active recognition per model at a time. The SoundTrigger service will handle + * concurrent recognition requests by different users/applications on the same model. + * The implementation returns a unique handle used by other functions (unload_sound_model(), + * start_recognition(), etc... + */ + int (*load_sound_model)(const struct sound_trigger_hw_device *dev, + struct sound_trigger_sound_model *sound_model, + sound_model_callback_t callback, + void *cookie, + sound_model_handle_t *handle); + + /* + * Unload a sound model. A sound model can be unloaded to make room for a new one to overcome + * implementation limitations. + */ + int (*unload_sound_model)(const struct sound_trigger_hw_device *dev, + sound_model_handle_t handle); + + /* Start recognition on a given model. Only one recognition active at a time per model. + * Once recognition succeeds of fails, the callback is called. + * TODO: group recognition configuration parameters into one struct and add key phrase options. + */ + int (*start_recognition)(const struct sound_trigger_hw_device *dev, + sound_model_handle_t sound_model_handle, + const struct sound_trigger_recognition_config *config, + recognition_callback_t callback, + void *cookie); + + /* Stop recognition on a given model. + * The implementation does not have to call the callback when stopped via this method. + */ + int (*stop_recognition)(const struct sound_trigger_hw_device *dev, + sound_model_handle_t sound_model_handle); +}; + +typedef struct sound_trigger_hw_device sound_trigger_hw_device_t; + +/** convenience API for opening and closing a supported device */ + +static inline int sound_trigger_hw_device_open(const struct hw_module_t* module, + struct sound_trigger_hw_device** device) +{ + return module->methods->open(module, SOUND_TRIGGER_HARDWARE_INTERFACE, + (struct hw_device_t**)device); +} + +static inline int sound_trigger_hw_device_close(struct sound_trigger_hw_device* device) +{ + return device->common.close(&device->common); +} + +__END_DECLS + +#endif // ANDROID_SOUND_TRIGGER_HAL_H diff --git a/third_party/android_hardware_libhardware/include/hardware/tv_input.h b/third_party/android_hardware_libhardware/include/hardware/tv_input.h new file mode 100644 index 00000000000000..456b06e1fdebc9 --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/tv_input.h @@ -0,0 +1,408 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_TV_INPUT_INTERFACE_H +#define ANDROID_TV_INPUT_INTERFACE_H + +#include +#include +#include + +#include +#include +#include + +__BEGIN_DECLS + +/* + * Module versioning information for the TV input hardware module, based on + * tv_input_module_t.common.module_api_version. + * + * Version History: + * + * TV_INPUT_MODULE_API_VERSION_0_1: + * Initial TV input hardware module API. + * + */ + +#define TV_INPUT_MODULE_API_VERSION_0_1 HARDWARE_MODULE_API_VERSION(0, 1) + +#define TV_INPUT_DEVICE_API_VERSION_0_1 HARDWARE_DEVICE_API_VERSION(0, 1) + +/* + * The id of this module + */ +#define TV_INPUT_HARDWARE_MODULE_ID "tv_input" + +#define TV_INPUT_DEFAULT_DEVICE "default" + +/*****************************************************************************/ + +/* + * Every hardware module must have a data structure named HAL_MODULE_INFO_SYM + * and the fields of this data structure must begin with hw_module_t + * followed by module specific information. + */ +typedef struct tv_input_module { + struct hw_module_t common; +} tv_input_module_t; + +/*****************************************************************************/ + +enum { + /* Generic hardware. */ + TV_INPUT_TYPE_OTHER_HARDWARE = 1, + /* Tuner. (e.g. built-in terrestrial tuner) */ + TV_INPUT_TYPE_TUNER = 2, + TV_INPUT_TYPE_COMPOSITE = 3, + TV_INPUT_TYPE_SVIDEO = 4, + TV_INPUT_TYPE_SCART = 5, + TV_INPUT_TYPE_COMPONENT = 6, + TV_INPUT_TYPE_VGA = 7, + TV_INPUT_TYPE_DVI = 8, + /* Physical HDMI port. (e.g. HDMI 1) */ + TV_INPUT_TYPE_HDMI = 9, + TV_INPUT_TYPE_DISPLAY_PORT = 10, +}; +typedef uint32_t tv_input_type_t; + +typedef struct tv_input_device_info { + /* Device ID */ + int device_id; + + /* Type of physical TV input. */ + tv_input_type_t type; + + union { + struct { + /* HDMI port ID number */ + uint32_t port_id; + } hdmi; + + /* TODO: add other type specific information. */ + + int32_t type_info_reserved[16]; + }; + + /* TODO: Add capability if necessary. */ + + /* + * Audio info + * + * audio_type == AUDIO_DEVICE_NONE if this input has no audio. + */ + audio_devices_t audio_type; + const char* audio_address; + + int32_t reserved[16]; +} tv_input_device_info_t; + +/* See tv_input_event_t for more details. */ +enum { + /* + * Hardware notifies the framework that a device is available. + * + * Note that DEVICE_AVAILABLE and DEVICE_UNAVAILABLE events do not represent + * hotplug events (i.e. plugging cable into or out of the physical port). + * These events notify the framework whether the port is available or not. + * For a concrete example, when a user plugs in or pulls out the HDMI cable + * from a HDMI port, it does not generate DEVICE_AVAILABLE and/or + * DEVICE_UNAVAILABLE events. However, if a user inserts a pluggable USB + * tuner into the Android device, it will generate a DEVICE_AVAILABLE event + * and when the port is removed, it should generate a DEVICE_UNAVAILABLE + * event. + * + * For hotplug events, please see STREAM_CONFIGURATION_CHANGED for more + * details. + * + * HAL implementation should register devices by using this event when the + * device boots up. The framework will recognize device reported via this + * event only. In addition, the implementation could use this event to + * notify the framework that a removable TV input device (such as USB tuner + * as stated in the example above) is attached. + */ + TV_INPUT_EVENT_DEVICE_AVAILABLE = 1, + /* + * Hardware notifies the framework that a device is unavailable. + * + * HAL implementation should generate this event when a device registered + * by TV_INPUT_EVENT_DEVICE_AVAILABLE is no longer available. For example, + * the event can indicate that a USB tuner is plugged out from the Android + * device. + * + * Note that this event is not for indicating cable plugged out of the port; + * for that purpose, the implementation should use + * STREAM_CONFIGURATION_CHANGED event. This event represents the port itself + * being no longer available. + */ + TV_INPUT_EVENT_DEVICE_UNAVAILABLE = 2, + /* + * Stream configurations are changed. Client should regard all open streams + * at the specific device are closed, and should call + * get_stream_configurations() again, opening some of them if necessary. + * + * HAL implementation should generate this event when the available stream + * configurations change for any reason. A typical use case of this event + * would be to notify the framework that the input signal has changed + * resolution, or that the cable is plugged out so that the number of + * available streams is 0. + * + * The implementation may use this event to indicate hotplug status of the + * port. the framework regards input devices with no available streams as + * disconnected, so the implementation can generate this event with no + * available streams to indicate that this device is disconnected, and vice + * versa. + */ + TV_INPUT_EVENT_STREAM_CONFIGURATIONS_CHANGED = 3, + /* + * Hardware is done with capture request with the buffer. Client can assume + * ownership of the buffer again. + * + * HAL implementation should generate this event after request_capture() if + * it succeeded. The event shall have the buffer with the captured image. + */ + TV_INPUT_EVENT_CAPTURE_SUCCEEDED = 4, + /* + * Hardware met a failure while processing a capture request or client + * canceled the request. Client can assume ownership of the buffer again. + * + * The event is similar to TV_INPUT_EVENT_CAPTURE_SUCCEEDED, but HAL + * implementation generates this event upon a failure to process + * request_capture(), or a request cancellation. + */ + TV_INPUT_EVENT_CAPTURE_FAILED = 5, +}; +typedef uint32_t tv_input_event_type_t; + +typedef struct tv_input_capture_result { + /* Device ID */ + int device_id; + + /* Stream ID */ + int stream_id; + + /* Sequence number of the request */ + uint32_t seq; + + /* + * The buffer passed to hardware in request_capture(). The content of + * buffer is undefined (although buffer itself is valid) for + * TV_INPUT_CAPTURE_FAILED event. + */ + buffer_handle_t buffer; + + /* + * Error code for the request. -ECANCELED if request is cancelled; other + * error codes are unknown errors. + */ + int error_code; +} tv_input_capture_result_t; + +typedef struct tv_input_event { + tv_input_event_type_t type; + + union { + /* + * TV_INPUT_EVENT_DEVICE_AVAILABLE: all fields are relevant + * TV_INPUT_EVENT_DEVICE_UNAVAILABLE: only device_id is relevant + * TV_INPUT_EVENT_STREAM_CONFIGURATIONS_CHANGED: only device_id is + * relevant + */ + tv_input_device_info_t device_info; + /* + * TV_INPUT_EVENT_CAPTURE_SUCCEEDED: error_code is not relevant + * TV_INPUT_EVENT_CAPTURE_FAILED: all fields are relevant + */ + tv_input_capture_result_t capture_result; + }; +} tv_input_event_t; + +typedef struct tv_input_callback_ops { + /* + * event contains the type of the event and additional data if necessary. + * The event object is guaranteed to be valid only for the duration of the + * call. + * + * data is an object supplied at device initialization, opaque to the + * hardware. +     */ + void (*notify)(struct tv_input_device* dev, + tv_input_event_t* event, void* data); +} tv_input_callback_ops_t; + +enum { + TV_STREAM_TYPE_INDEPENDENT_VIDEO_SOURCE = 1, + TV_STREAM_TYPE_BUFFER_PRODUCER = 2, +}; +typedef uint32_t tv_stream_type_t; + +typedef struct tv_stream_config { + /* + * ID number of the stream. This value is used to identify the whole stream + * configuration. + */ + int stream_id; + + /* Type of the stream */ + tv_stream_type_t type; + + /* Max width/height of the stream. */ + uint32_t max_video_width; + uint32_t max_video_height; +} tv_stream_config_t; + +typedef struct buffer_producer_stream { + /* + * IN/OUT: Width / height of the stream. Client may request for specific + * size but hardware may change it. Client must allocate buffers with + * specified width and height. + */ + uint32_t width; + uint32_t height; + + /* OUT: Client must set this usage when allocating buffer. */ + uint32_t usage; + + /* OUT: Client must allocate a buffer with this format. */ + uint32_t format; + + /* OUT: Client must allocate buffers based on this count. */ + uint32_t buffer_count; +} buffer_producer_stream_t; + +typedef struct tv_stream { + /* IN: ID in the stream configuration */ + int stream_id; + + /* OUT: Type of the stream (for convenience) */ + tv_stream_type_t type; + + /* Data associated with the stream for client's use */ + union { + /* OUT: A native handle describing the sideband stream source */ + native_handle_t* sideband_stream_source_handle; + + /* IN/OUT: Details are in buffer_producer_stream_t */ + buffer_producer_stream_t buffer_producer; + }; +} tv_stream_t; + +/* + * Every device data structure must begin with hw_device_t + * followed by module specific public methods and attributes. + */ +typedef struct tv_input_device { + struct hw_device_t common; + + /* + * initialize: + * + * Provide callbacks to the device and start operation. At first, no device + * is available and after initialize() completes, currently available + * devices including static devices should notify via callback. + * + * Framework owns callbacks object. + * + * data is a framework-owned object which would be sent back to the + * framework for each callback notifications. + * + * Return 0 on success. + */ + int (*initialize)(struct tv_input_device* dev, + const tv_input_callback_ops_t* callback, void* data); + + /* + * get_stream_configurations: + * + * Get stream configurations for a specific device. An input device may have + * multiple configurations. + * + * The configs object is guaranteed to be valid only until the next call to + * get_stream_configurations() or STREAM_CONFIGURATIONS_CHANGED event. + * + * Return 0 on success. + */ + int (*get_stream_configurations)(const struct tv_input_device* dev, + int device_id, int* num_configurations, + const tv_stream_config_t** configs); + + /* + * open_stream: + * + * Open a stream with given stream ID. Caller owns stream object, and the + * populated data is only valid until the stream is closed. + * + * Return 0 on success; -EBUSY if the client should close other streams to + * open the stream; -EEXIST if the stream with the given ID is already open; + * -EINVAL if device_id and/or stream_id are invalid; other non-zero value + * denotes unknown error. + */ + int (*open_stream)(struct tv_input_device* dev, int device_id, + tv_stream_t* stream); + + /* + * close_stream: + * + * Close a stream to a device. data in tv_stream_t* object associated with + * the stream_id is obsolete once this call finishes. + * + * Return 0 on success; -ENOENT if the stream is not open; -EINVAL if + * device_id and/or stream_id are invalid. + */ + int (*close_stream)(struct tv_input_device* dev, int device_id, + int stream_id); + + /* + * request_capture: + * + * Request buffer capture for a stream. This is only valid for buffer + * producer streams. The buffer should be created with size, format and + * usage specified in the stream. Framework provides seq in an + * increasing sequence per each stream. Hardware should provide the picture + * in a chronological order according to seq. For example, if two + * requests are being processed at the same time, the request with the + * smaller seq should get an earlier frame. + * + * The framework releases the ownership of the buffer upon calling this + * function. When the buffer is filled, hardware notifies the framework + * via TV_INPUT_EVENT_CAPTURE_FINISHED callback, and the ownership is + * transferred back to framework at that time. + * + * Return 0 on success; -ENOENT if the stream is not open; -EINVAL if + * device_id and/or stream_id are invalid; -EWOULDBLOCK if HAL cannot take + * additional requests until it releases a buffer. + */ + int (*request_capture)(struct tv_input_device* dev, int device_id, + int stream_id, buffer_handle_t buffer, uint32_t seq); + + /* + * cancel_capture: + * + * Cancel an ongoing capture. Hardware should release the buffer as soon as + * possible via TV_INPUT_EVENT_CAPTURE_FAILED callback. + * + * Return 0 on success; -ENOENT if the stream is not open; -EINVAL if + * device_id, stream_id, and/or seq are invalid. + */ + int (*cancel_capture)(struct tv_input_device* dev, int device_id, + int stream_id, uint32_t seq); + + void* reserved[16]; +} tv_input_device_t; + +__END_DECLS + +#endif // ANDROID_TV_INPUT_INTERFACE_H diff --git a/third_party/android_hardware_libhardware/include/hardware/vibrator.h b/third_party/android_hardware_libhardware/include/hardware/vibrator.h new file mode 100644 index 00000000000000..92b1fd0051388b --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/vibrator.h @@ -0,0 +1,74 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _HARDWARE_VIBRATOR_H +#define _HARDWARE_VIBRATOR_H + +#include + +__BEGIN_DECLS + +#define VIBRATOR_API_VERSION HARDWARE_MODULE_API_VERSION(1,0) + +/** + * The id of this module + */ +#define VIBRATOR_HARDWARE_MODULE_ID "vibrator" + +/** + * The id of the main vibrator device + */ +#define VIBRATOR_DEVICE_ID_MAIN "main_vibrator" + +struct vibrator_device; +typedef struct vibrator_device { + /** + * Common methods of the vibrator device. This *must* be the first member of + * vibrator_device as users of this structure will cast a hw_device_t to + * vibrator_device pointer in contexts where it's known the hw_device_t references a + * vibrator_device. + */ + struct hw_device_t common; + + /** Turn on vibrator + * + * What happens when this function is called while the the timeout of a + * previous call has not expired is implementation dependent. + * + * @param timeout_ms number of milliseconds to vibrate + * + * @return 0 in case of success, negative errno code else + */ + int (*vibrator_on)(struct vibrator_device* vibradev, unsigned int timeout_ms); + + /** Turn off vibrator + * + * It is not guaranteed that the vibrator will be immediately stopped: the + * behaviour is implementation dependent. + * + * @return 0 in case of success, negative errno code else + */ + int (*vibrator_off)(struct vibrator_device* vibradev); +} vibrator_device_t; + +static inline int vibrator_open(const struct hw_module_t* module, vibrator_device_t** device) +{ + return module->methods->open(module, VIBRATOR_DEVICE_ID_MAIN, (struct hw_device_t**)device); +} + +__END_DECLS + +#endif // _HARDWARE_VIBRATOR_H diff --git a/third_party/android_hardware_libhardware/include/hardware/wipower.h b/third_party/android_hardware_libhardware/include/hardware/wipower.h new file mode 100644 index 00000000000000..eb3a0ee0d54f5c --- /dev/null +++ b/third_party/android_hardware_libhardware/include/hardware/wipower.h @@ -0,0 +1,119 @@ +/* + * Copyright (c) 2013-2015, The Linux Foundation. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are + * met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of The Linux Foundation nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS + * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR + * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE + * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN + * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ANDROID_INCLUDE_WIPOWER_H +#define ANDROID_INCLUDE_WIPOWER_H + +#include +#include +#include +#include + +#include +#include + +__BEGIN_DECLS + +typedef enum { + OFF =0, + ON +} wipower_state_t; + + +typedef struct { + +unsigned char optional; +unsigned short rect_voltage; +unsigned short rect_current; +unsigned short out_voltage; +unsigned short out_current; +unsigned char temp; +unsigned short rect_voltage_min; +unsigned short rect_voltage_set; +unsigned short rect_voltage_max; +unsigned char alert; +unsigned short rfu1; +unsigned char rfu2; + +}__attribute__((packed)) wipower_dyn_data_t; + +/** Bluetooth Enable/Disable Callback. */ +typedef void (*wipower_state_changed_callback)(wipower_state_t state); + + +typedef void (*wipower_alerts)(unsigned char alert); + + +typedef void (*wipower_dynamic_data)(wipower_dyn_data_t* alert_data); + + +typedef void (*wipower_power_apply)(unsigned char power_flag); + +typedef void (*callback_thread_event)(bt_cb_thread_evt evt); + +/** Bluetooth DM callback structure. */ +typedef struct { + /** set to sizeof(wipower_callbacks_t) */ + size_t size; + wipower_state_changed_callback wipower_state_changed_cb; + wipower_alerts wipower_alert; + wipower_dynamic_data wipower_data; + wipower_power_apply wipower_power_event; + callback_thread_event callback_thread_event; +} wipower_callbacks_t; + + +/** Represents the standard Wipower interface. */ +typedef struct { + /** set to sizeof(wipower_interface_t) */ + size_t size; + + /** Initialize Wipower modules*/ + int (*init)(wipower_callbacks_t *wp_callbacks); + + /** Enable/Disable Wipower charging */ + int (*enable)(bool enable); + + int (*set_current_limit)(short value); + + unsigned char (*get_current_limit)(void); + + wipower_state_t (*get_state)(void); + + /** Enable/Disable Wipower charging */ + int (*enable_alerts)(bool enable); + + int (*enable_data_notify)(bool enable); + int (*enable_power_apply)(bool enable, bool on, bool time_flag); +} wipower_interface_t; + + +__END_DECLS + +#endif /* ANDROID_INCLUDE_WIPOWER_H */ diff --git a/third_party/android_system_core/include/cutils/android_reboot.h b/third_party/android_system_core/include/cutils/android_reboot.h new file mode 100644 index 00000000000000..a3861a02dcd9ed --- /dev/null +++ b/third_party/android_system_core/include/cutils/android_reboot.h @@ -0,0 +1,39 @@ +/* + * Copyright 2011, The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_ANDROID_REBOOT_H__ +#define __CUTILS_ANDROID_REBOOT_H__ + +#include + +__BEGIN_DECLS + +/* Commands */ +#define ANDROID_RB_RESTART 0xDEAD0001 +#define ANDROID_RB_POWEROFF 0xDEAD0002 +#define ANDROID_RB_RESTART2 0xDEAD0003 + +/* Properties */ +#define ANDROID_RB_PROPERTY "sys.powerctl" + +int android_reboot(int cmd, int flags, const char *arg); +int android_reboot_with_callback( + int cmd, int flags, const char *arg, + void (*cb_on_remount)(const struct mntent*)); + +__END_DECLS + +#endif /* __CUTILS_ANDROID_REBOOT_H__ */ diff --git a/third_party/android_system_core/include/cutils/aref.h b/third_party/android_system_core/include/cutils/aref.h new file mode 100644 index 00000000000000..3bd36ea04c5481 --- /dev/null +++ b/third_party/android_system_core/include/cutils/aref.h @@ -0,0 +1,58 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _CUTILS_AREF_H_ +#define _CUTILS_AREF_H_ + +#include +#include + +#include + +__BEGIN_DECLS + +#define AREF_TO_ITEM(aref, container, member) \ + (container *) (((char*) (aref)) - offsetof(container, member)) + +struct aref +{ + volatile int32_t count; +}; + +static inline void aref_init(struct aref *r) +{ + r->count = 1; +} + +static inline int32_t aref_count(struct aref *r) +{ + return r->count; +} + +static inline void aref_get(struct aref *r) +{ + android_atomic_inc(&r->count); +} + +static inline void aref_put(struct aref *r, void (*release)(struct aref *)) +{ + if (android_atomic_dec(&r->count) == 1) + release(r); +} + +__END_DECLS + +#endif // _CUTILS_AREF_H_ diff --git a/third_party/android_system_core/include/cutils/ashmem.h b/third_party/android_system_core/include/cutils/ashmem.h new file mode 100644 index 00000000000000..25b233e6a1bf67 --- /dev/null +++ b/third_party/android_system_core/include/cutils/ashmem.h @@ -0,0 +1,45 @@ +/* cutils/ashmem.h + ** + ** Copyright 2008 The Android Open Source Project + ** + ** This file is dual licensed. It may be redistributed and/or modified + ** under the terms of the Apache 2.0 License OR version 2 of the GNU + ** General Public License. + */ + +#ifndef _CUTILS_ASHMEM_H +#define _CUTILS_ASHMEM_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +int ashmem_create_region(const char *name, size_t size); +int ashmem_set_prot_region(int fd, int prot); +int ashmem_pin_region(int fd, size_t offset, size_t len); +int ashmem_unpin_region(int fd, size_t offset, size_t len); +int ashmem_get_size_region(int fd); + +#ifdef __cplusplus +} +#endif + +#ifndef __ASHMEMIOC /* in case someone included too */ + +#define ASHMEM_NAME_LEN 256 + +#define ASHMEM_NAME_DEF "dev/ashmem" + +/* Return values from ASHMEM_PIN: Was the mapping purged while unpinned? */ +#define ASHMEM_NOT_PURGED 0 +#define ASHMEM_WAS_PURGED 1 + +/* Return values from ASHMEM_UNPIN: Is the mapping now pinned or unpinned? */ +#define ASHMEM_IS_UNPINNED 0 +#define ASHMEM_IS_PINNED 1 + +#endif /* ! __ASHMEMIOC */ + +#endif /* _CUTILS_ASHMEM_H */ diff --git a/third_party/android_system_core/include/cutils/atomic.h b/third_party/android_system_core/include/cutils/atomic.h new file mode 100644 index 00000000000000..ded972acb262aa --- /dev/null +++ b/third_party/android_system_core/include/cutils/atomic.h @@ -0,0 +1,237 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_CUTILS_ATOMIC_H +#define ANDROID_CUTILS_ATOMIC_H + +#include +#include +#include + +#ifndef ANDROID_ATOMIC_INLINE +#define ANDROID_ATOMIC_INLINE static inline +#endif + +/* + * A handful of basic atomic operations. + * THESE ARE HERE FOR LEGACY REASONS ONLY. AVOID. + * + * PREFERRED ALTERNATIVES: + * - Use C++/C/pthread locks/mutexes whenever there is not a + * convincing reason to do otherwise. Note that very clever and + * complicated, but correct, lock-free code is often slower than + * using locks, especially where nontrivial data structures + * are involved. + * - C11 stdatomic.h. + * - Where supported, C++11 std::atomic . + * + * PLEASE STOP READING HERE UNLESS YOU ARE TRYING TO UNDERSTAND + * OR UPDATE OLD CODE. + * + * The "acquire" and "release" terms can be defined intuitively in terms + * of the placement of memory barriers in a simple lock implementation: + * - wait until compare-and-swap(lock-is-free --> lock-is-held) succeeds + * - barrier + * - [do work] + * - barrier + * - store(lock-is-free) + * In very crude terms, the initial (acquire) barrier prevents any of the + * "work" from happening before the lock is held, and the later (release) + * barrier ensures that all of the work happens before the lock is released. + * (Think of cached writes, cache read-ahead, and instruction reordering + * around the CAS and store instructions.) + * + * The barriers must apply to both the compiler and the CPU. Note it is + * legal for instructions that occur before an "acquire" barrier to be + * moved down below it, and for instructions that occur after a "release" + * barrier to be moved up above it. + * + * The ARM-driven implementation we use here is short on subtlety, + * and actually requests a full barrier from the compiler and the CPU. + * The only difference between acquire and release is in whether they + * are issued before or after the atomic operation with which they + * are associated. To ease the transition to C/C++ atomic intrinsics, + * you should not rely on this, and instead assume that only the minimal + * acquire/release protection is provided. + * + * NOTE: all int32_t* values are expected to be aligned on 32-bit boundaries. + * If they are not, atomicity is not guaranteed. + */ + +/* + * Basic arithmetic and bitwise operations. These all provide a + * barrier with "release" ordering, and return the previous value. + * + * These have the same characteristics (e.g. what happens on overflow) + * as the equivalent non-atomic C operations. + */ +ANDROID_ATOMIC_INLINE +int32_t android_atomic_inc(volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + /* Int32_t, if it exists, is the same as int_least32_t. */ + return atomic_fetch_add_explicit(a, 1, memory_order_release); +} + +ANDROID_ATOMIC_INLINE +int32_t android_atomic_dec(volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return atomic_fetch_sub_explicit(a, 1, memory_order_release); +} + +ANDROID_ATOMIC_INLINE +int32_t android_atomic_add(int32_t value, volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return atomic_fetch_add_explicit(a, value, memory_order_release); +} + +ANDROID_ATOMIC_INLINE +int32_t android_atomic_and(int32_t value, volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return atomic_fetch_and_explicit(a, value, memory_order_release); +} + +ANDROID_ATOMIC_INLINE +int32_t android_atomic_or(int32_t value, volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return atomic_fetch_or_explicit(a, value, memory_order_release); +} + +/* + * Perform an atomic load with "acquire" or "release" ordering. + * + * Note that the notion of a "release" ordering for a load does not + * really fit into the C11 or C++11 memory model. The extra ordering + * is normally observable only by code using memory_order_relaxed + * atomics, or data races. In the rare cases in which such ordering + * is called for, use memory_order_relaxed atomics and a leading + * atomic_thread_fence (typically with memory_order_acquire, + * not memory_order_release!) instead. If you do not understand + * this comment, you are in the vast majority, and should not be + * using release loads or replacing them with anything other than + * locks or default sequentially consistent atomics. + */ +ANDROID_ATOMIC_INLINE +int32_t android_atomic_acquire_load(volatile const int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return atomic_load_explicit(a, memory_order_acquire); +} + +ANDROID_ATOMIC_INLINE +int32_t android_atomic_release_load(volatile const int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + atomic_thread_fence(memory_order_seq_cst); + /* Any reasonable clients of this interface would probably prefer */ + /* something weaker. But some remaining clients seem to be */ + /* abusing this API in strange ways, e.g. by using it as a fence. */ + /* Thus we are conservative until we can get rid of remaining */ + /* clients (and this function). */ + return atomic_load_explicit(a, memory_order_relaxed); +} + +/* + * Perform an atomic store with "acquire" or "release" ordering. + * + * Note that the notion of an "acquire" ordering for a store does not + * really fit into the C11 or C++11 memory model. The extra ordering + * is normally observable only by code using memory_order_relaxed + * atomics, or data races. In the rare cases in which such ordering + * is called for, use memory_order_relaxed atomics and a trailing + * atomic_thread_fence (typically with memory_order_release, + * not memory_order_acquire!) instead. + */ +ANDROID_ATOMIC_INLINE +void android_atomic_acquire_store(int32_t value, volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + atomic_store_explicit(a, value, memory_order_relaxed); + atomic_thread_fence(memory_order_seq_cst); + /* Again overly conservative to accomodate weird clients. */ +} + +ANDROID_ATOMIC_INLINE +void android_atomic_release_store(int32_t value, volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + atomic_store_explicit(a, value, memory_order_release); +} + +/* + * Compare-and-set operation with "acquire" or "release" ordering. + * + * This returns zero if the new value was successfully stored, which will + * only happen when *addr == oldvalue. + * + * (The return value is inverted from implementations on other platforms, + * but matches the ARM ldrex/strex result.) + * + * Implementations that use the release CAS in a loop may be less efficient + * than possible, because we re-issue the memory barrier on each iteration. + */ +ANDROID_ATOMIC_INLINE +int android_atomic_acquire_cas(int32_t oldvalue, int32_t newvalue, + volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return (int)(!atomic_compare_exchange_strong_explicit( + a, &oldvalue, newvalue, + memory_order_acquire, + memory_order_acquire)); +} + +ANDROID_ATOMIC_INLINE +int android_atomic_release_cas(int32_t oldvalue, int32_t newvalue, + volatile int32_t* addr) +{ + volatile atomic_int_least32_t* a = (volatile atomic_int_least32_t*)addr; + return (int)(!atomic_compare_exchange_strong_explicit( + a, &oldvalue, newvalue, + memory_order_release, + memory_order_relaxed)); +} + +/* + * Fence primitives. + */ +ANDROID_ATOMIC_INLINE +void android_compiler_barrier(void) +{ + __asm__ __volatile__ ("" : : : "memory"); + /* Could probably also be: */ + /* atomic_signal_fence(memory_order_seq_cst); */ +} + +ANDROID_ATOMIC_INLINE +void android_memory_barrier(void) +{ + atomic_thread_fence(memory_order_seq_cst); +} + +/* + * Aliases for code using an older version of this header. These are now + * deprecated and should not be used. The definitions will be removed + * in a future release. + */ +#define android_atomic_write android_atomic_release_store +#define android_atomic_cmpxchg android_atomic_release_cas + +#endif // ANDROID_CUTILS_ATOMIC_H diff --git a/third_party/android_system_core/include/cutils/bitops.h b/third_party/android_system_core/include/cutils/bitops.h new file mode 100644 index 00000000000000..045830d90bd6f5 --- /dev/null +++ b/third_party/android_system_core/include/cutils/bitops.h @@ -0,0 +1,120 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_BITOPS_H +#define __CUTILS_BITOPS_H + +#include +#include +#include +#include + +__BEGIN_DECLS + +/* + * Bitmask Operations + * + * Note this doesn't provide any locking/exclusion, and isn't atomic. + * Additionally no bounds checking is done on the bitmask array. + * + * Example: + * + * int num_resources; + * unsigned int resource_bits[BITS_TO_WORDS(num_resources)]; + * bitmask_init(resource_bits, num_resources); + * ... + * int bit = bitmask_ffz(resource_bits, num_resources); + * bitmask_set(resource_bits, bit); + * ... + * if (bitmask_test(resource_bits, bit)) { ... } + * ... + * bitmask_clear(resource_bits, bit); + * + */ + +#define BITS_PER_WORD (sizeof(unsigned int) * 8) +#define BITS_TO_WORDS(x) (((x) + BITS_PER_WORD - 1) / BITS_PER_WORD) +#define BIT_IN_WORD(x) ((x) % BITS_PER_WORD) +#define BIT_WORD(x) ((x) / BITS_PER_WORD) +#define BIT_MASK(x) (1 << BIT_IN_WORD(x)) + +static inline void bitmask_init(unsigned int *bitmask, int num_bits) +{ + memset(bitmask, 0, BITS_TO_WORDS(num_bits)*sizeof(unsigned int)); +} + +static inline int bitmask_ffz(unsigned int *bitmask, int num_bits) +{ + int bit, result; + size_t i; + + for (i = 0; i < BITS_TO_WORDS(num_bits); i++) { + bit = ffs(~bitmask[i]); + if (bit) { + // ffs is 1-indexed, return 0-indexed result + bit--; + result = BITS_PER_WORD * i + bit; + if (result >= num_bits) + return -1; + return result; + } + } + return -1; +} + +static inline int bitmask_weight(unsigned int *bitmask, int num_bits) +{ + size_t i; + int weight = 0; + + for (i = 0; i < BITS_TO_WORDS(num_bits); i++) + weight += __builtin_popcount(bitmask[i]); + return weight; +} + +static inline void bitmask_set(unsigned int *bitmask, int bit) +{ + bitmask[BIT_WORD(bit)] |= BIT_MASK(bit); +} + +static inline void bitmask_clear(unsigned int *bitmask, int bit) +{ + bitmask[BIT_WORD(bit)] &= ~BIT_MASK(bit); +} + +static inline bool bitmask_test(unsigned int *bitmask, int bit) +{ + return bitmask[BIT_WORD(bit)] & BIT_MASK(bit); +} + +static inline int popcount(unsigned int x) +{ + return __builtin_popcount(x); +} + +static inline int popcountl(unsigned long x) +{ + return __builtin_popcountl(x); +} + +static inline int popcountll(unsigned long long x) +{ + return __builtin_popcountll(x); +} + +__END_DECLS + +#endif /* __CUTILS_BITOPS_H */ diff --git a/third_party/android_system_core/include/cutils/compiler.h b/third_party/android_system_core/include/cutils/compiler.h new file mode 100644 index 00000000000000..70f884a1e701f5 --- /dev/null +++ b/third_party/android_system_core/include/cutils/compiler.h @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_CUTILS_COMPILER_H +#define ANDROID_CUTILS_COMPILER_H + +/* + * helps the compiler's optimizer predicting branches + */ + +#ifdef __cplusplus +# define CC_LIKELY( exp ) (__builtin_expect( !!(exp), true )) +# define CC_UNLIKELY( exp ) (__builtin_expect( !!(exp), false )) +#else +# define CC_LIKELY( exp ) (__builtin_expect( !!(exp), 1 )) +# define CC_UNLIKELY( exp ) (__builtin_expect( !!(exp), 0 )) +#endif + +/** + * exports marked symbols + * + * if used on a C++ class declaration, this macro must be inserted + * after the "class" keyword. For instance: + * + * template + * class ANDROID_API Singleton { } + */ + +#define ANDROID_API __attribute__((visibility("default"))) + +#endif // ANDROID_CUTILS_COMPILER_H diff --git a/third_party/android_system_core/include/cutils/config_utils.h b/third_party/android_system_core/include/cutils/config_utils.h new file mode 100644 index 00000000000000..2dea6f19fa1882 --- /dev/null +++ b/third_party/android_system_core/include/cutils/config_utils.h @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_CONFIG_UTILS_H +#define __CUTILS_CONFIG_UTILS_H + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct cnode cnode; + + +struct cnode +{ + cnode *next; + cnode *first_child; + cnode *last_child; + const char *name; + const char *value; +}; + +/* parse a text string into a config node tree */ +void config_load(cnode *root, char *data); + +/* parse a file into a config node tree */ +void config_load_file(cnode *root, const char *fn); + +/* create a single config node */ +cnode* config_node(const char *name, const char *value); + +/* locate a named child of a config node */ +cnode* config_find(cnode *root, const char *name); + +/* look up a child by name and return the boolean value */ +int config_bool(cnode *root, const char *name, int _default); + +/* look up a child by name and return the string value */ +const char* config_str(cnode *root, const char *name, const char *_default); + +/* add a named child to a config node (or modify it if it already exists) */ +void config_set(cnode *root, const char *name, const char *value); + +/* free a config node tree */ +void config_free(cnode *root); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/third_party/android_system_core/include/cutils/debugger.h b/third_party/android_system_core/include/cutils/debugger.h new file mode 100644 index 00000000000000..285e1afcd7d28e --- /dev/null +++ b/third_party/android_system_core/include/cutils/debugger.h @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_DEBUGGER_H +#define __CUTILS_DEBUGGER_H + +#include +#include + +__BEGIN_DECLS + +#define DEBUGGER_SOCKET_NAME "android:debuggerd" +#define DEBUGGER32_SOCKET_NAME "android:debuggerd32" +#define DEBUGGER64_SOCKET_NAME DEBUGGER_SOCKET_NAME + +typedef enum { + // dump a crash + DEBUGGER_ACTION_CRASH, + // dump a tombstone file + DEBUGGER_ACTION_DUMP_TOMBSTONE, + // dump a backtrace only back to the socket + DEBUGGER_ACTION_DUMP_BACKTRACE, +} debugger_action_t; + +// Make sure that all values have a fixed size so that this structure +// is the same for 32 bit and 64 bit processes. +// NOTE: Any changes to this structure must also be reflected in +// bionic/linker/debugger.cpp. +typedef struct __attribute__((packed)) { + int32_t action; + pid_t tid; + uint64_t abort_msg_address; + int32_t original_si_code; +} debugger_msg_t; + +/* Dumps a process backtrace, registers, and stack to a tombstone file (requires root). + * Stores the tombstone path in the provided buffer. + * Returns 0 on success, -1 on error. + */ +int dump_tombstone(pid_t tid, char* pathbuf, size_t pathlen); + +/* Dumps a process backtrace, registers, and stack to a tombstone file (requires root). + * Stores the tombstone path in the provided buffer. + * If reading debugger data from debuggerd ever takes longer than timeout_secs + * seconds, then stop and return an error. + * Returns 0 on success, -1 on error. + */ +int dump_tombstone_timeout(pid_t tid, char* pathbuf, size_t pathlen, int timeout_secs); + +/* Dumps a process backtrace only to the specified file (requires root). + * Returns 0 on success, -1 on error. + */ +int dump_backtrace_to_file(pid_t tid, int fd); + +/* Dumps a process backtrace only to the specified file (requires root). + * If reading debugger data from debuggerd ever takes longer than timeout_secs + * seconds, then stop and return an error. + * Returns 0 on success, -1 on error. + */ +int dump_backtrace_to_file_timeout(pid_t tid, int fd, int timeout_secs); + +__END_DECLS + +#endif /* __CUTILS_DEBUGGER_H */ diff --git a/third_party/android_system_core/include/cutils/fs.h b/third_party/android_system_core/include/cutils/fs.h new file mode 100644 index 00000000000000..70f0b929195f80 --- /dev/null +++ b/third_party/android_system_core/include/cutils/fs.h @@ -0,0 +1,71 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_FS_H +#define __CUTILS_FS_H + +#include +#include + +/* + * TEMP_FAILURE_RETRY is defined by some, but not all, versions of + * . (Alas, it is not as standard as we'd hoped!) So, if it's + * not already defined, then define it here. + */ +#ifndef TEMP_FAILURE_RETRY +/* Used to retry syscalls that can return EINTR. */ +#define TEMP_FAILURE_RETRY(exp) ({ \ + typeof (exp) _rc; \ + do { \ + _rc = (exp); \ + } while (_rc == -1 && errno == EINTR); \ + _rc; }) +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Ensure that directory exists with given mode and owners. + */ +extern int fs_prepare_dir(const char* path, mode_t mode, uid_t uid, gid_t gid); + +/* + * Read single plaintext integer from given file, correctly handling files + * partially written with fs_write_atomic_int(). + */ +extern int fs_read_atomic_int(const char* path, int* value); + +/* + * Write single plaintext integer to given file, creating backup while + * in progress. + */ +extern int fs_write_atomic_int(const char* path, int value); + +/* + * Ensure that all directories along given path exist, creating parent + * directories as needed. Validates that given path is absolute and that + * it contains no relative "." or ".." paths or symlinks. Last path segment + * is treated as filename and ignored, unless the path ends with "/". + */ +extern int fs_mkdirs(const char* path, mode_t mode); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_FS_H */ diff --git a/third_party/android_system_core/include/cutils/hashmap.h b/third_party/android_system_core/include/cutils/hashmap.h new file mode 100644 index 00000000000000..5cb344c152beb3 --- /dev/null +++ b/third_party/android_system_core/include/cutils/hashmap.h @@ -0,0 +1,150 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * Hash map. + */ + +#ifndef __HASHMAP_H +#define __HASHMAP_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** A hash map. */ +typedef struct Hashmap Hashmap; + +/** + * Creates a new hash map. Returns NULL if memory allocation fails. + * + * @param initialCapacity number of expected entries + * @param hash function which hashes keys + * @param equals function which compares keys for equality + */ +Hashmap* hashmapCreate(size_t initialCapacity, + int (*hash)(void* key), bool (*equals)(void* keyA, void* keyB)); + +/** + * Frees the hash map. Does not free the keys or values themselves. + */ +void hashmapFree(Hashmap* map); + +/** + * Hashes the memory pointed to by key with the given size. Useful for + * implementing hash functions. + */ +int hashmapHash(void* key, size_t keySize); + +/** + * Puts value for the given key in the map. Returns pre-existing value if + * any. + * + * If memory allocation fails, this function returns NULL, the map's size + * does not increase, and errno is set to ENOMEM. + */ +void* hashmapPut(Hashmap* map, void* key, void* value); + +/** + * Gets a value from the map. Returns NULL if no entry for the given key is + * found or if the value itself is NULL. + */ +void* hashmapGet(Hashmap* map, void* key); + +/** + * Returns true if the map contains an entry for the given key. + */ +bool hashmapContainsKey(Hashmap* map, void* key); + +/** + * Gets the value for a key. If a value is not found, this function gets a + * value and creates an entry using the given callback. + * + * If memory allocation fails, the callback is not called, this function + * returns NULL, and errno is set to ENOMEM. + */ +void* hashmapMemoize(Hashmap* map, void* key, + void* (*initialValue)(void* key, void* context), void* context); + +/** + * Removes an entry from the map. Returns the removed value or NULL if no + * entry was present. + */ +void* hashmapRemove(Hashmap* map, void* key); + +/** + * Gets the number of entries in this map. + */ +size_t hashmapSize(Hashmap* map); + +/** + * Invokes the given callback on each entry in the map. Stops iterating if + * the callback returns false. + */ +void hashmapForEach(Hashmap* map, + bool (*callback)(void* key, void* value, void* context), + void* context); + +/** + * Concurrency support. + */ + +/** + * Locks the hash map so only the current thread can access it. + */ +void hashmapLock(Hashmap* map); + +/** + * Unlocks the hash map so other threads can access it. + */ +void hashmapUnlock(Hashmap* map); + +/** + * Key utilities. + */ + +/** + * Hashes int keys. 'key' is a pointer to int. + */ +int hashmapIntHash(void* key); + +/** + * Compares two int keys for equality. + */ +bool hashmapIntEquals(void* keyA, void* keyB); + +/** + * For debugging. + */ + +/** + * Gets current capacity. + */ +size_t hashmapCurrentCapacity(Hashmap* map); + +/** + * Counts the number of entry collisions. + */ +size_t hashmapCountCollisions(Hashmap* map); + +#ifdef __cplusplus +} +#endif + +#endif /* __HASHMAP_H */ diff --git a/third_party/android_system_core/include/cutils/iosched_policy.h b/third_party/android_system_core/include/cutils/iosched_policy.h new file mode 100644 index 00000000000000..25b87bac0a4a3c --- /dev/null +++ b/third_party/android_system_core/include/cutils/iosched_policy.h @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_IOSCHED_POLICY_H +#define __CUTILS_IOSCHED_POLICY_H + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum { + IoSchedClass_NONE, + IoSchedClass_RT, + IoSchedClass_BE, + IoSchedClass_IDLE, +} IoSchedClass; + +extern int android_set_ioprio(int pid, IoSchedClass clazz, int ioprio); +extern int android_get_ioprio(int pid, IoSchedClass *clazz, int *ioprio); + +extern int android_set_rt_ioprio(int pid, int rt); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_IOSCHED_POLICY_H */ diff --git a/third_party/android_system_core/include/cutils/jstring.h b/third_party/android_system_core/include/cutils/jstring.h new file mode 100644 index 00000000000000..a3426081a0be04 --- /dev/null +++ b/third_party/android_system_core/include/cutils/jstring.h @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_STRING16_H +#define __CUTILS_STRING16_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#if __STDC_VERSION__ < 201112L && __cplusplus < 201103L + typedef uint16_t char16_t; +#endif + // otherwise char16_t is a keyword with the right semantics + +extern char * strndup16to8 (const char16_t* s, size_t n); +extern size_t strnlen16to8 (const char16_t* s, size_t n); +extern char * strncpy16to8 (char *dest, const char16_t*s, size_t n); + +extern char16_t * strdup8to16 (const char* s, size_t *out_len); +extern size_t strlen8to16 (const char* utf8Str); +extern char16_t * strcpy8to16 (char16_t *dest, const char*s, size_t *out_len); +extern char16_t * strcpylen8to16 (char16_t *dest, const char*s, int length, + size_t *out_len); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_STRING16_H */ diff --git a/third_party/android_system_core/include/cutils/klog.h b/third_party/android_system_core/include/cutils/klog.h new file mode 100644 index 00000000000000..295d62be376795 --- /dev/null +++ b/third_party/android_system_core/include/cutils/klog.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _CUTILS_KLOG_H_ +#define _CUTILS_KLOG_H_ + +#include +#include +#include + +__BEGIN_DECLS + +void klog_init(void); +int klog_get_level(void); +void klog_set_level(int level); +/* TODO: void klog_close(void); - and make klog_fd users thread safe. */ + +void klog_write(int level, const char *fmt, ...) + __attribute__ ((format(printf, 2, 3))); +void klog_writev(int level, const struct iovec* iov, int iov_count); + +__END_DECLS + +#define KLOG_ERROR_LEVEL 3 +#define KLOG_WARNING_LEVEL 4 +#define KLOG_NOTICE_LEVEL 5 +#define KLOG_INFO_LEVEL 6 +#define KLOG_DEBUG_LEVEL 7 + +#define KLOG_ERROR(tag,x...) klog_write(KLOG_ERROR_LEVEL, "<3>" tag ": " x) +#define KLOG_WARNING(tag,x...) klog_write(KLOG_WARNING_LEVEL, "<4>" tag ": " x) +#define KLOG_NOTICE(tag,x...) klog_write(KLOG_NOTICE_LEVEL, "<5>" tag ": " x) +#define KLOG_INFO(tag,x...) klog_write(KLOG_INFO_LEVEL, "<6>" tag ": " x) +#define KLOG_DEBUG(tag,x...) klog_write(KLOG_DEBUG_LEVEL, "<7>" tag ": " x) + +#define KLOG_DEFAULT_LEVEL 3 /* messages <= this level are logged */ + +#endif diff --git a/third_party/android_system_core/include/cutils/list.h b/third_party/android_system_core/include/cutils/list.h new file mode 100644 index 00000000000000..4ba2cfd4990062 --- /dev/null +++ b/third_party/android_system_core/include/cutils/list.h @@ -0,0 +1,88 @@ +/* + * Copyright (C) 2008-2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _CUTILS_LIST_H_ +#define _CUTILS_LIST_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif /* __cplusplus */ + +struct listnode +{ + struct listnode *next; + struct listnode *prev; +}; + +#define node_to_item(node, container, member) \ + (container *) (((char*) (node)) - offsetof(container, member)) + +#define list_declare(name) \ + struct listnode name = { \ + .next = &name, \ + .prev = &name, \ + } + +#define list_for_each(node, list) \ + for (node = (list)->next; node != (list); node = node->next) + +#define list_for_each_reverse(node, list) \ + for (node = (list)->prev; node != (list); node = node->prev) + +#define list_for_each_safe(node, n, list) \ + for (node = (list)->next, n = node->next; \ + node != (list); \ + node = n, n = node->next) + +static inline void list_init(struct listnode *node) +{ + node->next = node; + node->prev = node; +} + +static inline void list_add_tail(struct listnode *head, struct listnode *item) +{ + item->next = head; + item->prev = head->prev; + head->prev->next = item; + head->prev = item; +} + +static inline void list_add_head(struct listnode *head, struct listnode *item) +{ + item->next = head->next; + item->prev = head; + head->next->prev = item; + head->next = item; +} + +static inline void list_remove(struct listnode *item) +{ + item->next->prev = item->prev; + item->prev->next = item->next; +} + +#define list_empty(list) ((list) == (list)->next) +#define list_head(list) ((list)->next) +#define list_tail(list) ((list)->prev) + +#ifdef __cplusplus +}; +#endif /* __cplusplus */ + +#endif diff --git a/third_party/android_system_core/include/cutils/log.h b/third_party/android_system_core/include/cutils/log.h new file mode 100644 index 00000000000000..0e0248e50fa7aa --- /dev/null +++ b/third_party/android_system_core/include/cutils/log.h @@ -0,0 +1 @@ +#include diff --git a/third_party/android_system_core/include/cutils/memory.h b/third_party/android_system_core/include/cutils/memory.h new file mode 100644 index 00000000000000..4d26882556bfc4 --- /dev/null +++ b/third_party/android_system_core/include/cutils/memory.h @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_CUTILS_MEMORY_H +#define ANDROID_CUTILS_MEMORY_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* size is given in bytes and must be multiple of 2 */ +void android_memset16(uint16_t* dst, uint16_t value, size_t size); + +/* size is given in bytes and must be multiple of 4 */ +void android_memset32(uint32_t* dst, uint32_t value, size_t size); + +#if defined(__GLIBC__) || defined(_WIN32) +/* Declaration of strlcpy() for platforms that don't already have it. */ +size_t strlcpy(char *dst, const char *src, size_t size); +#endif + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif // ANDROID_CUTILS_MEMORY_H diff --git a/third_party/android_system_core/include/cutils/misc.h b/third_party/android_system_core/include/cutils/misc.h new file mode 100644 index 00000000000000..0de505f277c18e --- /dev/null +++ b/third_party/android_system_core/include/cutils/misc.h @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_MISC_H +#define __CUTILS_MISC_H + +#ifdef __cplusplus +extern "C" { +#endif + + /* Load an entire file into a malloc'd chunk of memory + * that is length_of_file + 1 (null terminator). If + * sz is non-zero, return the size of the file via sz. + * Returns 0 on failure. + */ +extern void *load_file(const char *fn, unsigned *sz); + + /* This is the range of UIDs (and GIDs) that are reserved + * for assigning to applications. + */ +#define FIRST_APPLICATION_UID 10000 +#define LAST_APPLICATION_UID 99999 + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_MISC_H */ diff --git a/third_party/android_system_core/include/cutils/multiuser.h b/third_party/android_system_core/include/cutils/multiuser.h new file mode 100644 index 00000000000000..635ddb13587a95 --- /dev/null +++ b/third_party/android_system_core/include/cutils/multiuser.h @@ -0,0 +1,41 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_MULTIUSER_H +#define __CUTILS_MULTIUSER_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +// NOTE: keep in sync with android.os.UserId + +#define MULTIUSER_APP_PER_USER_RANGE 100000 + +typedef uid_t userid_t; +typedef uid_t appid_t; + +extern userid_t multiuser_get_user_id(uid_t uid); +extern appid_t multiuser_get_app_id(uid_t uid); +extern uid_t multiuser_get_uid(userid_t userId, appid_t appId); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_MULTIUSER_H */ diff --git a/third_party/android_system_core/include/cutils/native_handle.h b/third_party/android_system_core/include/cutils/native_handle.h new file mode 100644 index 00000000000000..268c5d3f51b7f2 --- /dev/null +++ b/third_party/android_system_core/include/cutils/native_handle.h @@ -0,0 +1,69 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef NATIVE_HANDLE_H_ +#define NATIVE_HANDLE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct native_handle +{ + int version; /* sizeof(native_handle_t) */ + int numFds; /* number of file-descriptors at &data[0] */ + int numInts; /* number of ints at &data[numFds] */ + int data[0]; /* numFds + numInts ints */ +} native_handle_t; + +/* + * native_handle_close + * + * closes the file descriptors contained in this native_handle_t + * + * return 0 on success, or a negative error code on failure + * + */ +int native_handle_close(const native_handle_t* h); + + +/* + * native_handle_create + * + * creates a native_handle_t and initializes it. must be destroyed with + * native_handle_delete(). + * + */ +native_handle_t* native_handle_create(int numFds, int numInts); + +/* + * native_handle_delete + * + * frees a native_handle_t allocated with native_handle_create(). + * This ONLY frees the memory allocated for the native_handle_t, but doesn't + * close the file descriptors; which can be achieved with native_handle_close(). + * + * return 0 on success, or a negative error code on failure + * + */ +int native_handle_delete(native_handle_t* h); + + +#ifdef __cplusplus +} +#endif + +#endif /* NATIVE_HANDLE_H_ */ diff --git a/third_party/android_system_core/include/cutils/open_memstream.h b/third_party/android_system_core/include/cutils/open_memstream.h new file mode 100644 index 00000000000000..c1a81ebbcbd81e --- /dev/null +++ b/third_party/android_system_core/include/cutils/open_memstream.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_OPEN_MEMSTREAM_H__ +#define __CUTILS_OPEN_MEMSTREAM_H__ + +#include + +#if defined(__APPLE__) + +#ifdef __cplusplus +extern "C" { +#endif + +FILE* open_memstream(char** bufp, size_t* sizep); + +#ifdef __cplusplus +} +#endif + +#endif /* __APPLE__ */ + +#endif /*__CUTILS_OPEN_MEMSTREAM_H__*/ diff --git a/third_party/android_system_core/include/cutils/partition_utils.h b/third_party/android_system_core/include/cutils/partition_utils.h new file mode 100644 index 00000000000000..72ca80d3505c08 --- /dev/null +++ b/third_party/android_system_core/include/cutils/partition_utils.h @@ -0,0 +1,26 @@ +/* + * Copyright 2011, The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_PARTITION_WIPED_H__ +#define __CUTILS_PARTITION_WIPED_H__ + +__BEGIN_DECLS + +int partition_wiped(char *source); + +__END_DECLS + +#endif /* __CUTILS_PARTITION_WIPED_H__ */ diff --git a/third_party/android_system_core/include/cutils/process_name.h b/third_party/android_system_core/include/cutils/process_name.h new file mode 100644 index 00000000000000..1e72e5c3ad3087 --- /dev/null +++ b/third_party/android_system_core/include/cutils/process_name.h @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * Gives the current process a name. + */ + +#ifndef __PROCESS_NAME_H +#define __PROCESS_NAME_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Sets the current process name. + * + * Warning: This leaks a string every time you call it. Use judiciously! + */ +void set_process_name(const char* process_name); + +/** Gets the current process name. */ +const char* get_process_name(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __PROCESS_NAME_H */ diff --git a/third_party/android_system_core/include/cutils/properties.h b/third_party/android_system_core/include/cutils/properties.h new file mode 100644 index 00000000000000..24aa224f64da08 --- /dev/null +++ b/third_party/android_system_core/include/cutils/properties.h @@ -0,0 +1,133 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_PROPERTIES_H +#define __CUTILS_PROPERTIES_H + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* System properties are *small* name value pairs managed by the +** property service. If your data doesn't fit in the provided +** space it is not appropriate for a system property. +** +** WARNING: system/bionic/include/sys/system_properties.h also defines +** these, but with different names. (TODO: fix that) +*/ +#define PROPERTY_KEY_MAX PROP_NAME_MAX +#define PROPERTY_VALUE_MAX PROP_VALUE_MAX + +/* property_get: returns the length of the value which will never be +** greater than PROPERTY_VALUE_MAX - 1 and will always be zero terminated. +** (the length does not include the terminating zero). +** +** If the property read fails or returns an empty value, the default +** value is used (if nonnull). +*/ +int property_get(const char *key, char *value, const char *default_value); + +/* property_get_bool: returns the value of key coerced into a +** boolean. If the property is not set, then the default value is returned. +** +* The following is considered to be true (1): +** "1", "true", "y", "yes", "on" +** +** The following is considered to be false (0): +** "0", "false", "n", "no", "off" +** +** The conversion is whitespace-sensitive (e.g. " off" will not be false). +** +** If no property with this key is set (or the key is NULL) or the boolean +** conversion fails, the default value is returned. +**/ +int8_t property_get_bool(const char *key, int8_t default_value); + +/* property_get_int64: returns the value of key truncated and coerced into a +** int64_t. If the property is not set, then the default value is used. +** +** The numeric conversion is identical to strtoimax with the base inferred: +** - All digits up to the first non-digit characters are read +** - The longest consecutive prefix of digits is converted to a long +** +** Valid strings of digits are: +** - An optional sign character + or - +** - An optional prefix indicating the base (otherwise base 10 is assumed) +** -- 0 prefix is octal +** -- 0x / 0X prefix is hex +** +** Leading/trailing whitespace is ignored. Overflow/underflow will cause +** numeric conversion to fail. +** +** If no property with this key is set (or the key is NULL) or the numeric +** conversion fails, the default value is returned. +**/ +int64_t property_get_int64(const char *key, int64_t default_value); + +/* property_get_int32: returns the value of key truncated and coerced into an +** int32_t. If the property is not set, then the default value is used. +** +** The numeric conversion is identical to strtoimax with the base inferred: +** - All digits up to the first non-digit characters are read +** - The longest consecutive prefix of digits is converted to a long +** +** Valid strings of digits are: +** - An optional sign character + or - +** - An optional prefix indicating the base (otherwise base 10 is assumed) +** -- 0 prefix is octal +** -- 0x / 0X prefix is hex +** +** Leading/trailing whitespace is ignored. Overflow/underflow will cause +** numeric conversion to fail. +** +** If no property with this key is set (or the key is NULL) or the numeric +** conversion fails, the default value is returned. +**/ +int32_t property_get_int32(const char *key, int32_t default_value); + +/* property_set: returns 0 on success, < 0 on failure +*/ +int property_set(const char *key, const char *value); + +int property_list(void (*propfn)(const char *key, const char *value, void *cookie), void *cookie); + +#if defined(__BIONIC_FORTIFY) + +extern int __property_get_real(const char *, char *, const char *) + __asm__(__USER_LABEL_PREFIX__ "property_get"); +__errordecl(__property_get_too_small_error, "property_get() called with too small of a buffer"); + +__BIONIC_FORTIFY_INLINE +int property_get(const char *key, char *value, const char *default_value) { + size_t bos = __bos(value); + if (bos < PROPERTY_VALUE_MAX) { + __property_get_too_small_error(); + } + return __property_get_real(key, value, default_value); +} + +#endif + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/third_party/android_system_core/include/cutils/qtaguid.h b/third_party/android_system_core/include/cutils/qtaguid.h new file mode 100644 index 00000000000000..f8550fda83b253 --- /dev/null +++ b/third_party/android_system_core/include/cutils/qtaguid.h @@ -0,0 +1,66 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_QTAGUID_H +#define __CUTILS_QTAGUID_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Set tags (and owning UIDs) for network sockets. +*/ +extern int qtaguid_tagSocket(int sockfd, int tag, uid_t uid); + +/* + * Untag a network socket before closing. +*/ +extern int qtaguid_untagSocket(int sockfd); + +/* + * For the given uid, switch counter sets. + * The kernel only keeps a limited number of sets. + * 2 for now. + */ +extern int qtaguid_setCounterSet(int counterSetNum, uid_t uid); + +/* + * Delete all tag info that relates to the given tag an uid. + * If the tag is 0, then ALL info about the uid is freeded. + * The delete data also affects active tagged socketd, which are + * then untagged. + * The calling process can only operate on its own tags. + * Unless it is part of the happy AID_NET_BW_ACCT group. + * In which case it can clobber everything. + */ +extern int qtaguid_deleteTagData(int tag, uid_t uid); + +/* + * Enable/disable qtaguid functionnality at a lower level. + * When pacified, the kernel will accept commands but do nothing. + */ +extern int qtaguid_setPacifier(int on); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_QTAG_UID_H */ diff --git a/third_party/android_system_core/include/cutils/record_stream.h b/third_party/android_system_core/include/cutils/record_stream.h new file mode 100644 index 00000000000000..bfac87a53cac9f --- /dev/null +++ b/third_party/android_system_core/include/cutils/record_stream.h @@ -0,0 +1,43 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * A simple utility for reading fixed records out of a stream fd + */ + +#ifndef _CUTILS_RECORD_STREAM_H +#define _CUTILS_RECORD_STREAM_H + +#ifdef __cplusplus +extern "C" { +#endif + + +typedef struct RecordStream RecordStream; + +extern RecordStream *record_stream_new(int fd, size_t maxRecordLen); +extern void record_stream_free(RecordStream *p_rs); + +extern int record_stream_get_next (RecordStream *p_rs, void ** p_outRecord, + size_t *p_outRecordLen); + +#ifdef __cplusplus +} +#endif + + +#endif /*_CUTILS_RECORD_STREAM_H*/ + diff --git a/third_party/android_system_core/include/cutils/sched_policy.h b/third_party/android_system_core/include/cutils/sched_policy.h new file mode 100644 index 00000000000000..6a8d570b2cb2a1 --- /dev/null +++ b/third_party/android_system_core/include/cutils/sched_policy.h @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_SCHED_POLICY_H +#define __CUTILS_SCHED_POLICY_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Keep in sync with THREAD_GROUP_* in frameworks/base/core/java/android/os/Process.java */ +typedef enum { + SP_DEFAULT = -1, + SP_BACKGROUND = 0, + SP_FOREGROUND = 1, + SP_SYSTEM = 2, // can't be used with set_sched_policy() + SP_AUDIO_APP = 3, + SP_AUDIO_SYS = 4, + SP_CNT, + SP_MAX = SP_CNT - 1, + SP_SYSTEM_DEFAULT = SP_FOREGROUND, +} SchedPolicy; + +extern int set_cpuset_policy(int tid, SchedPolicy policy); + +/* Assign thread tid to the cgroup associated with the specified policy. + * If the thread is a thread group leader, that is it's gettid() == getpid(), + * then the other threads in the same thread group are _not_ affected. + * On platforms which support gettid(), zero tid means current thread. + * Return value: 0 for success, or -errno for error. + */ +extern int set_sched_policy(int tid, SchedPolicy policy); + +/* Return the policy associated with the cgroup of thread tid via policy pointer. + * On platforms which support gettid(), zero tid means current thread. + * Return value: 0 for success, or -1 for error and set errno. + */ +extern int get_sched_policy(int tid, SchedPolicy *policy); + +/* Return a displayable string corresponding to policy. + * Return value: non-NULL NUL-terminated name of unspecified length; + * the caller is responsible for displaying the useful part of the string. + */ +extern const char *get_sched_policy_name(SchedPolicy policy); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_SCHED_POLICY_H */ diff --git a/third_party/android_system_core/include/cutils/sockets.h b/third_party/android_system_core/include/cutils/sockets.h new file mode 100644 index 00000000000000..f8076ca452b86e --- /dev/null +++ b/third_party/android_system_core/include/cutils/sockets.h @@ -0,0 +1,104 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_SOCKETS_H +#define __CUTILS_SOCKETS_H + +#include +#include +#include +#include +#include + +#ifdef HAVE_WINSOCK +#include +typedef int socklen_t; +#else +#include +#endif + +#define ANDROID_SOCKET_ENV_PREFIX "ANDROID_SOCKET_" +#define ANDROID_SOCKET_DIR "/dev/socket" + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * android_get_control_socket - simple helper function to get the file + * descriptor of our init-managed Unix domain socket. `name' is the name of the + * socket, as given in init.rc. Returns -1 on error. + * + * This is inline and not in libcutils proper because we want to use this in + * third-party daemons with minimal modification. + */ +static inline int android_get_control_socket(const char *name) +{ + char key[64]; + snprintf(key, sizeof(key), ANDROID_SOCKET_ENV_PREFIX "%s", name); + + const char* val = getenv(key); + if (!val) { + return -1; + } + + errno = 0; + int fd = strtol(val, NULL, 10); + if (errno) { + return -1; + } + + return fd; +} + +/* + * See also android.os.LocalSocketAddress.Namespace + */ +// Linux "abstract" (non-filesystem) namespace +#define ANDROID_SOCKET_NAMESPACE_ABSTRACT 0 +// Android "reserved" (/dev/socket) namespace +#define ANDROID_SOCKET_NAMESPACE_RESERVED 1 +// Normal filesystem namespace +#define ANDROID_SOCKET_NAMESPACE_FILESYSTEM 2 + +extern int socket_loopback_client(int port, int type); +extern int socket_network_client(const char *host, int port, int type); +extern int socket_network_client_timeout(const char *host, int port, int type, + int timeout); +extern int socket_loopback_server(int port, int type); +extern int socket_local_server(const char *name, int namespaceId, int type); +extern int socket_local_server_bind(int s, const char *name, int namespaceId); +extern int socket_local_client_connect(int fd, + const char *name, int namespaceId, int type); +extern int socket_local_client(const char *name, int namespaceId, int type); +extern int socket_inaddr_any_server(int port, int type); + +/* + * socket_peer_is_trusted - Takes a socket which is presumed to be a + * connected local socket (e.g. AF_LOCAL) and returns whether the peer + * (the userid that owns the process on the other end of that socket) + * is one of the two trusted userids, root or shell. + * + * Note: This only works as advertised on the Android OS and always + * just returns true when called on other operating systems. + */ +extern bool socket_peer_is_trusted(int fd); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_SOCKETS_H */ diff --git a/third_party/android_system_core/include/cutils/str_parms.h b/third_party/android_system_core/include/cutils/str_parms.h new file mode 100644 index 00000000000000..aa1435a080e2ef --- /dev/null +++ b/third_party/android_system_core/include/cutils/str_parms.h @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_STR_PARMS_H +#define __CUTILS_STR_PARMS_H + +#include +#include + +__BEGIN_DECLS + +struct str_parms; + +struct str_parms *str_parms_create(void); +struct str_parms *str_parms_create_str(const char *_string); +void str_parms_destroy(struct str_parms *str_parms); + +void str_parms_del(struct str_parms *str_parms, const char *key); + +int str_parms_add_str(struct str_parms *str_parms, const char *key, + const char *value); +int str_parms_add_int(struct str_parms *str_parms, const char *key, int value); + +int str_parms_add_float(struct str_parms *str_parms, const char *key, + float value); + +// Returns non-zero if the str_parms contains the specified key. +int str_parms_has_key(struct str_parms *str_parms, const char *key); + +// Gets value associated with the specified key (if present), placing it in the buffer +// pointed to by the out_val parameter. Returns the length of the returned string value. +// If 'key' isn't in the parms, then return -ENOENT (-2) and leave 'out_val' untouched. +int str_parms_get_str(struct str_parms *str_parms, const char *key, + char *out_val, int len); +int str_parms_get_int(struct str_parms *str_parms, const char *key, + int *out_val); +int str_parms_get_float(struct str_parms *str_parms, const char *key, + float *out_val); + +char *str_parms_to_str(struct str_parms *str_parms); + +/* debug */ +void str_parms_dump(struct str_parms *str_parms); + +__END_DECLS + +#endif /* __CUTILS_STR_PARMS_H */ diff --git a/third_party/android_system_core/include/cutils/threads.h b/third_party/android_system_core/include/cutils/threads.h new file mode 100644 index 00000000000000..5727494079f143 --- /dev/null +++ b/third_party/android_system_core/include/cutils/threads.h @@ -0,0 +1,148 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_CUTILS_THREADS_H +#define _LIBS_CUTILS_THREADS_H + +#include + +#if !defined(_WIN32) +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/***********************************************************************/ +/***********************************************************************/ +/***** *****/ +/***** local thread storage *****/ +/***** *****/ +/***********************************************************************/ +/***********************************************************************/ + +extern pid_t gettid(); + +#if !defined(_WIN32) + +typedef struct { + pthread_mutex_t lock; + int has_tls; + pthread_key_t tls; +} thread_store_t; + +#define THREAD_STORE_INITIALIZER { PTHREAD_MUTEX_INITIALIZER, 0, 0 } + +#else // !defined(_WIN32) + +typedef struct { + int lock_init; + int has_tls; + DWORD tls; + CRITICAL_SECTION lock; +} thread_store_t; + +#define THREAD_STORE_INITIALIZER { 0, 0, 0, {0, 0, 0, 0, 0, 0} } + +#endif // !defined(_WIN32) + +typedef void (*thread_store_destruct_t)(void* value); + +extern void* thread_store_get(thread_store_t* store); + +extern void thread_store_set(thread_store_t* store, + void* value, + thread_store_destruct_t destroy); + +/***********************************************************************/ +/***********************************************************************/ +/***** *****/ +/***** mutexes *****/ +/***** *****/ +/***********************************************************************/ +/***********************************************************************/ + +#if !defined(_WIN32) + +typedef pthread_mutex_t mutex_t; + +#define MUTEX_INITIALIZER PTHREAD_MUTEX_INITIALIZER + +static __inline__ void mutex_lock(mutex_t* lock) +{ + pthread_mutex_lock(lock); +} +static __inline__ void mutex_unlock(mutex_t* lock) +{ + pthread_mutex_unlock(lock); +} +static __inline__ int mutex_init(mutex_t* lock) +{ + return pthread_mutex_init(lock, NULL); +} +static __inline__ void mutex_destroy(mutex_t* lock) +{ + pthread_mutex_destroy(lock); +} + +#else // !defined(_WIN32) + +typedef struct { + int init; + CRITICAL_SECTION lock[1]; +} mutex_t; + +#define MUTEX_INITIALIZER { 0, {{ NULL, 0, 0, NULL, NULL, 0 }} } + +static __inline__ void mutex_lock(mutex_t* lock) +{ + if (!lock->init) { + lock->init = 1; + InitializeCriticalSection( lock->lock ); + lock->init = 2; + } else while (lock->init != 2) + Sleep(10); + + EnterCriticalSection(lock->lock); +} + +static __inline__ void mutex_unlock(mutex_t* lock) +{ + LeaveCriticalSection(lock->lock); +} +static __inline__ int mutex_init(mutex_t* lock) +{ + InitializeCriticalSection(lock->lock); + lock->init = 2; + return 0; +} +static __inline__ void mutex_destroy(mutex_t* lock) +{ + if (lock->init) { + lock->init = 0; + DeleteCriticalSection(lock->lock); + } +} +#endif // !defined(_WIN32) + +#ifdef __cplusplus +} +#endif + +#endif /* _LIBS_CUTILS_THREADS_H */ diff --git a/third_party/android_system_core/include/cutils/trace.h b/third_party/android_system_core/include/cutils/trace.h new file mode 100644 index 00000000000000..e4ed17983d2dc1 --- /dev/null +++ b/third_party/android_system_core/include/cutils/trace.h @@ -0,0 +1,252 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_CUTILS_TRACE_H +#define _LIBS_CUTILS_TRACE_H + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +__BEGIN_DECLS + +/** + * The ATRACE_TAG macro can be defined before including this header to trace + * using one of the tags defined below. It must be defined to one of the + * following ATRACE_TAG_* macros. The trace tag is used to filter tracing in + * userland to avoid some of the runtime cost of tracing when it is not desired. + * + * Defining ATRACE_TAG to be ATRACE_TAG_ALWAYS will result in the tracing always + * being enabled - this should ONLY be done for debug code, as userland tracing + * has a performance cost even when the trace is not being recorded. Defining + * ATRACE_TAG to be ATRACE_TAG_NEVER or leaving ATRACE_TAG undefined will result + * in the tracing always being disabled. + * + * ATRACE_TAG_HAL should be bitwise ORed with the relevant tags for tracing + * within a hardware module. For example a camera hardware module would set: + * #define ATRACE_TAG (ATRACE_TAG_CAMERA | ATRACE_TAG_HAL) + * + * Keep these in sync with frameworks/base/core/java/android/os/Trace.java. + */ +#define ATRACE_TAG_NEVER 0 // This tag is never enabled. +#define ATRACE_TAG_ALWAYS (1<<0) // This tag is always enabled. +#define ATRACE_TAG_GRAPHICS (1<<1) +#define ATRACE_TAG_INPUT (1<<2) +#define ATRACE_TAG_VIEW (1<<3) +#define ATRACE_TAG_WEBVIEW (1<<4) +#define ATRACE_TAG_WINDOW_MANAGER (1<<5) +#define ATRACE_TAG_ACTIVITY_MANAGER (1<<6) +#define ATRACE_TAG_SYNC_MANAGER (1<<7) +#define ATRACE_TAG_AUDIO (1<<8) +#define ATRACE_TAG_VIDEO (1<<9) +#define ATRACE_TAG_CAMERA (1<<10) +#define ATRACE_TAG_HAL (1<<11) +#define ATRACE_TAG_APP (1<<12) +#define ATRACE_TAG_RESOURCES (1<<13) +#define ATRACE_TAG_DALVIK (1<<14) +#define ATRACE_TAG_RS (1<<15) +#define ATRACE_TAG_BIONIC (1<<16) +#define ATRACE_TAG_POWER (1<<17) +#define ATRACE_TAG_LAST ATRACE_TAG_POWER + +// Reserved for initialization. +#define ATRACE_TAG_NOT_READY (1LL<<63) + +#define ATRACE_TAG_VALID_MASK ((ATRACE_TAG_LAST - 1) | ATRACE_TAG_LAST) + +#ifndef ATRACE_TAG +#define ATRACE_TAG ATRACE_TAG_NEVER +#elif ATRACE_TAG > ATRACE_TAG_VALID_MASK +#error ATRACE_TAG must be defined to be one of the tags defined in cutils/trace.h +#endif + +/** + * Opens the trace file for writing and reads the property for initial tags. + * The atrace.tags.enableflags property sets the tags to trace. + * This function should not be explicitly called, the first call to any normal + * trace function will cause it to be run safely. + */ +void atrace_setup(); + +/** + * If tracing is ready, set atrace_enabled_tags to the system property + * debug.atrace.tags.enableflags. Can be used as a sysprop change callback. + */ +void atrace_update_tags(); + +/** + * Set whether the process is debuggable. By default the process is not + * considered debuggable. If the process is not debuggable then application- + * level tracing is not allowed unless the ro.debuggable system property is + * set to '1'. + */ +void atrace_set_debuggable(bool debuggable); + +/** + * Set whether tracing is enabled for the current process. This is used to + * prevent tracing within the Zygote process. + */ +void atrace_set_tracing_enabled(bool enabled); + +/** + * Flag indicating whether setup has been completed, initialized to 0. + * Nonzero indicates setup has completed. + * Note: This does NOT indicate whether or not setup was successful. + */ +extern atomic_bool atrace_is_ready; + +/** + * Set of ATRACE_TAG flags to trace for, initialized to ATRACE_TAG_NOT_READY. + * A value of zero indicates setup has failed. + * Any other nonzero value indicates setup has succeeded, and tracing is on. + */ +extern uint64_t atrace_enabled_tags; + +/** + * Handle to the kernel's trace buffer, initialized to -1. + * Any other value indicates setup has succeeded, and is a valid fd for tracing. + */ +extern int atrace_marker_fd; + +/** + * atrace_init readies the process for tracing by opening the trace_marker file. + * Calling any trace function causes this to be run, so calling it is optional. + * This can be explicitly run to avoid setup delay on first trace function. + */ +#define ATRACE_INIT() atrace_init() +static inline void atrace_init() +{ + if (CC_UNLIKELY(!atomic_load_explicit(&atrace_is_ready, memory_order_acquire))) { + atrace_setup(); + } +} + +/** + * Get the mask of all tags currently enabled. + * It can be used as a guard condition around more expensive trace calculations. + * Every trace function calls this, which ensures atrace_init is run. + */ +#define ATRACE_GET_ENABLED_TAGS() atrace_get_enabled_tags() +static inline uint64_t atrace_get_enabled_tags() +{ + atrace_init(); + return atrace_enabled_tags; +} + +/** + * Test if a given tag is currently enabled. + * Returns nonzero if the tag is enabled, otherwise zero. + * It can be used as a guard condition around more expensive trace calculations. + */ +#define ATRACE_ENABLED() atrace_is_tag_enabled(ATRACE_TAG) +static inline uint64_t atrace_is_tag_enabled(uint64_t tag) +{ + return atrace_get_enabled_tags() & tag; +} + +/** + * Trace the beginning of a context. name is used to identify the context. + * This is often used to time function execution. + */ +#define ATRACE_BEGIN(name) atrace_begin(ATRACE_TAG, name) +static inline void atrace_begin(uint64_t tag, const char* name) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + void atrace_begin_body(const char*); + atrace_begin_body(name); + } +} + +/** + * Trace the end of a context. + * This should match up (and occur after) a corresponding ATRACE_BEGIN. + */ +#define ATRACE_END() atrace_end(ATRACE_TAG) +static inline void atrace_end(uint64_t tag) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + char c = 'E'; + write(atrace_marker_fd, &c, 1); + } +} + +/** + * Trace the beginning of an asynchronous event. Unlike ATRACE_BEGIN/ATRACE_END + * contexts, asynchronous events do not need to be nested. The name describes + * the event, and the cookie provides a unique identifier for distinguishing + * simultaneous events. The name and cookie used to begin an event must be + * used to end it. + */ +#define ATRACE_ASYNC_BEGIN(name, cookie) \ + atrace_async_begin(ATRACE_TAG, name, cookie) +static inline void atrace_async_begin(uint64_t tag, const char* name, + int32_t cookie) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + void atrace_async_begin_body(const char*, int32_t); + atrace_async_begin_body(name, cookie); + } +} + +/** + * Trace the end of an asynchronous event. + * This should have a corresponding ATRACE_ASYNC_BEGIN. + */ +#define ATRACE_ASYNC_END(name, cookie) atrace_async_end(ATRACE_TAG, name, cookie) +static inline void atrace_async_end(uint64_t tag, const char* name, int32_t cookie) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + void atrace_async_end_body(const char*, int32_t); + atrace_async_end_body(name, cookie); + } +} + +/** + * Traces an integer counter value. name is used to identify the counter. + * This can be used to track how a value changes over time. + */ +#define ATRACE_INT(name, value) atrace_int(ATRACE_TAG, name, value) +static inline void atrace_int(uint64_t tag, const char* name, int32_t value) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + void atrace_int_body(const char*, int32_t); + atrace_int_body(name, value); + } +} + +/** + * Traces a 64-bit integer counter value. name is used to identify the + * counter. This can be used to track how a value changes over time. + */ +#define ATRACE_INT64(name, value) atrace_int64(ATRACE_TAG, name, value) +static inline void atrace_int64(uint64_t tag, const char* name, int64_t value) +{ + if (CC_UNLIKELY(atrace_is_tag_enabled(tag))) { + void atrace_int64_body(const char*, int64_t); + atrace_int64_body(name, value); + } +} + +__END_DECLS + +#endif // _LIBS_CUTILS_TRACE_H diff --git a/third_party/android_system_core/include/cutils/uevent.h b/third_party/android_system_core/include/cutils/uevent.h new file mode 100644 index 00000000000000..da1c2aae6b37e8 --- /dev/null +++ b/third_party/android_system_core/include/cutils/uevent.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CUTILS_UEVENT_H +#define __CUTILS_UEVENT_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +int uevent_open_socket(int buf_sz, bool passcred); +ssize_t uevent_kernel_multicast_recv(int socket, void *buffer, size_t length); +ssize_t uevent_kernel_multicast_uid_recv(int socket, void *buffer, size_t length, uid_t *uid); +ssize_t uevent_kernel_recv(int socket, void *buffer, size_t length, bool require_group, uid_t *uid); + +#ifdef __cplusplus +} +#endif + +#endif /* __CUTILS_UEVENT_H */ diff --git a/third_party/android_system_core/include/log/event_tag_map.h b/third_party/android_system_core/include/log/event_tag_map.h new file mode 100644 index 00000000000000..1653c61e9a4194 --- /dev/null +++ b/third_party/android_system_core/include/log/event_tag_map.h @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_CUTILS_EVENTTAGMAP_H +#define _LIBS_CUTILS_EVENTTAGMAP_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define EVENT_TAG_MAP_FILE "/system/etc/event-log-tags" + +struct EventTagMap; +typedef struct EventTagMap EventTagMap; + +/* + * Open the specified file as an event log tag map. + * + * Returns NULL on failure. + */ +EventTagMap* android_openEventTagMap(const char* fileName); + +/* + * Close the map. + */ +void android_closeEventTagMap(EventTagMap* map); + +/* + * Look up a tag by index. Returns the tag string, or NULL if not found. + */ +const char* android_lookupEventTag(const EventTagMap* map, int tag); + +#ifdef __cplusplus +} +#endif + +#endif /*_LIBS_CUTILS_EVENTTAGMAP_H*/ diff --git a/third_party/android_system_core/include/log/log.h b/third_party/android_system_core/include/log/log.h new file mode 100644 index 00000000000000..63a441a689e35c --- /dev/null +++ b/third_party/android_system_core/include/log/log.h @@ -0,0 +1,642 @@ +/* + * Copyright (C) 2005-2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// C/C++ logging functions. See the logging documentation for API details. +// +// We'd like these to be available from C code (in case we import some from +// somewhere), so this has a C interface. +// +// The output will be correct when the log file is shared between multiple +// threads and/or multiple processes so long as the operating system +// supports O_APPEND. These calls have mutex-protected data structures +// and so are NOT reentrant. Do not use LOG in a signal handler. +// +#ifndef _LIBS_LOG_LOG_H +#define _LIBS_LOG_LOG_H + +#include +#include +#include +#include +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +// --------------------------------------------------------------------- + +/* + * Normally we strip ALOGV (VERBOSE messages) from release builds. + * You can modify this (for example with "#define LOG_NDEBUG 0" + * at the top of your source file) to change that behavior. + */ +#ifndef LOG_NDEBUG +#ifdef NDEBUG +#define LOG_NDEBUG 1 +#else +#define LOG_NDEBUG 0 +#endif +#endif + +/* + * This is the local tag used for the following simplified + * logging macros. You can change this preprocessor definition + * before using the other macros to change the tag. + */ +#ifndef LOG_TAG +#define LOG_TAG NULL +#endif + +// --------------------------------------------------------------------- + +#ifndef __predict_false +#define __predict_false(exp) __builtin_expect((exp) != 0, 0) +#endif + +/* + * -DLINT_RLOG in sources that you want to enforce that all logging + * goes to the radio log buffer. If any logging goes to any of the other + * log buffers, there will be a compile or link error to highlight the + * problem. This is not a replacement for a full audit of the code since + * this only catches compiled code, not ifdef'd debug code. Options to + * defining this, either temporarily to do a spot check, or permanently + * to enforce, in all the communications trees; We have hopes to ensure + * that by supplying just the radio log buffer that the communications + * teams will have their one-stop shop for triaging issues. + */ +#ifndef LINT_RLOG + +/* + * Simplified macro to send a verbose log message using the current LOG_TAG. + */ +#ifndef ALOGV +#define __ALOGV(...) ((void)ALOG(LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) +#if LOG_NDEBUG +#define ALOGV(...) do { if (0) { __ALOGV(__VA_ARGS__); } } while (0) +#else +#define ALOGV(...) __ALOGV(__VA_ARGS__) +#endif +#endif + +#ifndef ALOGV_IF +#if LOG_NDEBUG +#define ALOGV_IF(cond, ...) ((void)0) +#else +#define ALOGV_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)ALOG(LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif +#endif + +/* + * Simplified macro to send a debug log message using the current LOG_TAG. + */ +#ifndef ALOGD +#define ALOGD(...) ((void)ALOG(LOG_DEBUG, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef ALOGD_IF +#define ALOGD_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)ALOG(LOG_DEBUG, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an info log message using the current LOG_TAG. + */ +#ifndef ALOGI +#define ALOGI(...) ((void)ALOG(LOG_INFO, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef ALOGI_IF +#define ALOGI_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)ALOG(LOG_INFO, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send a warning log message using the current LOG_TAG. + */ +#ifndef ALOGW +#define ALOGW(...) ((void)ALOG(LOG_WARN, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef ALOGW_IF +#define ALOGW_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)ALOG(LOG_WARN, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an error log message using the current LOG_TAG. + */ +#ifndef ALOGE +#define ALOGE(...) ((void)ALOG(LOG_ERROR, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef ALOGE_IF +#define ALOGE_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)ALOG(LOG_ERROR, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +// --------------------------------------------------------------------- + +/* + * Conditional based on whether the current LOG_TAG is enabled at + * verbose priority. + */ +#ifndef IF_ALOGV +#if LOG_NDEBUG +#define IF_ALOGV() if (false) +#else +#define IF_ALOGV() IF_ALOG(LOG_VERBOSE, LOG_TAG) +#endif +#endif + +/* + * Conditional based on whether the current LOG_TAG is enabled at + * debug priority. + */ +#ifndef IF_ALOGD +#define IF_ALOGD() IF_ALOG(LOG_DEBUG, LOG_TAG) +#endif + +/* + * Conditional based on whether the current LOG_TAG is enabled at + * info priority. + */ +#ifndef IF_ALOGI +#define IF_ALOGI() IF_ALOG(LOG_INFO, LOG_TAG) +#endif + +/* + * Conditional based on whether the current LOG_TAG is enabled at + * warn priority. + */ +#ifndef IF_ALOGW +#define IF_ALOGW() IF_ALOG(LOG_WARN, LOG_TAG) +#endif + +/* + * Conditional based on whether the current LOG_TAG is enabled at + * error priority. + */ +#ifndef IF_ALOGE +#define IF_ALOGE() IF_ALOG(LOG_ERROR, LOG_TAG) +#endif + + +// --------------------------------------------------------------------- + +/* + * Simplified macro to send a verbose system log message using the current LOG_TAG. + */ +#ifndef SLOGV +#define __SLOGV(...) \ + ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) +#if LOG_NDEBUG +#define SLOGV(...) do { if (0) { __SLOGV(__VA_ARGS__); } } while (0) +#else +#define SLOGV(...) __SLOGV(__VA_ARGS__) +#endif +#endif + +#ifndef SLOGV_IF +#if LOG_NDEBUG +#define SLOGV_IF(cond, ...) ((void)0) +#else +#define SLOGV_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif +#endif + +/* + * Simplified macro to send a debug system log message using the current LOG_TAG. + */ +#ifndef SLOGD +#define SLOGD(...) \ + ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_DEBUG, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef SLOGD_IF +#define SLOGD_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_DEBUG, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an info system log message using the current LOG_TAG. + */ +#ifndef SLOGI +#define SLOGI(...) \ + ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_INFO, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef SLOGI_IF +#define SLOGI_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_INFO, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send a warning system log message using the current LOG_TAG. + */ +#ifndef SLOGW +#define SLOGW(...) \ + ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_WARN, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef SLOGW_IF +#define SLOGW_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_WARN, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an error system log message using the current LOG_TAG. + */ +#ifndef SLOGE +#define SLOGE(...) \ + ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_ERROR, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef SLOGE_IF +#define SLOGE_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_SYSTEM, ANDROID_LOG_ERROR, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +#endif /* !LINT_RLOG */ + +// --------------------------------------------------------------------- + +/* + * Simplified macro to send a verbose radio log message using the current LOG_TAG. + */ +#ifndef RLOGV +#define __RLOGV(...) \ + ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) +#if LOG_NDEBUG +#define RLOGV(...) do { if (0) { __RLOGV(__VA_ARGS__); } } while (0) +#else +#define RLOGV(...) __RLOGV(__VA_ARGS__) +#endif +#endif + +#ifndef RLOGV_IF +#if LOG_NDEBUG +#define RLOGV_IF(cond, ...) ((void)0) +#else +#define RLOGV_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_VERBOSE, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif +#endif + +/* + * Simplified macro to send a debug radio log message using the current LOG_TAG. + */ +#ifndef RLOGD +#define RLOGD(...) \ + ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_DEBUG, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef RLOGD_IF +#define RLOGD_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_DEBUG, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an info radio log message using the current LOG_TAG. + */ +#ifndef RLOGI +#define RLOGI(...) \ + ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_INFO, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef RLOGI_IF +#define RLOGI_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_INFO, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send a warning radio log message using the current LOG_TAG. + */ +#ifndef RLOGW +#define RLOGW(...) \ + ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_WARN, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef RLOGW_IF +#define RLOGW_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_WARN, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + +/* + * Simplified macro to send an error radio log message using the current LOG_TAG. + */ +#ifndef RLOGE +#define RLOGE(...) \ + ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_ERROR, LOG_TAG, __VA_ARGS__)) +#endif + +#ifndef RLOGE_IF +#define RLOGE_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)__android_log_buf_print(LOG_ID_RADIO, ANDROID_LOG_ERROR, LOG_TAG, __VA_ARGS__)) \ + : (void)0 ) +#endif + + +// --------------------------------------------------------------------- + +/* + * Log a fatal error. If the given condition fails, this stops program + * execution like a normal assertion, but also generating the given message. + * It is NOT stripped from release builds. Note that the condition test + * is -inverted- from the normal assert() semantics. + */ +#ifndef LOG_ALWAYS_FATAL_IF +#define LOG_ALWAYS_FATAL_IF(cond, ...) \ + ( (__predict_false(cond)) \ + ? ((void)android_printAssert(#cond, LOG_TAG, ## __VA_ARGS__)) \ + : (void)0 ) +#endif + +#ifndef LOG_ALWAYS_FATAL +#define LOG_ALWAYS_FATAL(...) \ + ( ((void)android_printAssert(NULL, LOG_TAG, ## __VA_ARGS__)) ) +#endif + +/* + * Versions of LOG_ALWAYS_FATAL_IF and LOG_ALWAYS_FATAL that + * are stripped out of release builds. + */ +#if LOG_NDEBUG + +#ifndef LOG_FATAL_IF +#define LOG_FATAL_IF(cond, ...) ((void)0) +#endif +#ifndef LOG_FATAL +#define LOG_FATAL(...) ((void)0) +#endif + +#else + +#ifndef LOG_FATAL_IF +#define LOG_FATAL_IF(cond, ...) LOG_ALWAYS_FATAL_IF(cond, ## __VA_ARGS__) +#endif +#ifndef LOG_FATAL +#define LOG_FATAL(...) LOG_ALWAYS_FATAL(__VA_ARGS__) +#endif + +#endif + +/* + * Assertion that generates a log message when the assertion fails. + * Stripped out of release builds. Uses the current LOG_TAG. + */ +#ifndef ALOG_ASSERT +#define ALOG_ASSERT(cond, ...) LOG_FATAL_IF(!(cond), ## __VA_ARGS__) +//#define ALOG_ASSERT(cond) LOG_FATAL_IF(!(cond), "Assertion failed: " #cond) +#endif + +// --------------------------------------------------------------------- + +/* + * Basic log message macro. + * + * Example: + * ALOG(LOG_WARN, NULL, "Failed with error %d", errno); + * + * The second argument may be NULL or "" to indicate the "global" tag. + */ +#ifndef ALOG +#define ALOG(priority, tag, ...) \ + LOG_PRI(ANDROID_##priority, tag, __VA_ARGS__) +#endif + +/* + * Log macro that allows you to specify a number for the priority. + */ +#ifndef LOG_PRI +#define LOG_PRI(priority, tag, ...) \ + android_printLog(priority, tag, __VA_ARGS__) +#endif + +/* + * Log macro that allows you to pass in a varargs ("args" is a va_list). + */ +#ifndef LOG_PRI_VA +#define LOG_PRI_VA(priority, tag, fmt, args) \ + android_vprintLog(priority, NULL, tag, fmt, args) +#endif + +/* + * Conditional given a desired logging priority and tag. + */ +#ifndef IF_ALOG +#define IF_ALOG(priority, tag) \ + if (android_testLog(ANDROID_##priority, tag)) +#endif + +// --------------------------------------------------------------------- + +/* + * Event logging. + */ + +/* + * Event log entry types. These must match up with the declarations in + * java/android/android/util/EventLog.java. + */ +typedef enum { + EVENT_TYPE_INT = 0, + EVENT_TYPE_LONG = 1, + EVENT_TYPE_STRING = 2, + EVENT_TYPE_LIST = 3, + EVENT_TYPE_FLOAT = 4, +} AndroidEventLogType; +#define sizeof_AndroidEventLogType sizeof(typeof_AndroidEventLogType) +#define typeof_AndroidEventLogType unsigned char + +#ifndef LOG_EVENT_INT +#define LOG_EVENT_INT(_tag, _value) { \ + int intBuf = _value; \ + (void) android_btWriteLog(_tag, EVENT_TYPE_INT, &intBuf, \ + sizeof(intBuf)); \ + } +#endif +#ifndef LOG_EVENT_LONG +#define LOG_EVENT_LONG(_tag, _value) { \ + long long longBuf = _value; \ + (void) android_btWriteLog(_tag, EVENT_TYPE_LONG, &longBuf, \ + sizeof(longBuf)); \ + } +#endif +#ifndef LOG_EVENT_FLOAT +#define LOG_EVENT_FLOAT(_tag, _value) { \ + float floatBuf = _value; \ + (void) android_btWriteLog(_tag, EVENT_TYPE_FLOAT, &floatBuf, \ + sizeof(floatBuf)); \ + } +#endif +#ifndef LOG_EVENT_STRING +#define LOG_EVENT_STRING(_tag, _value) \ + (void) __android_log_bswrite(_tag, _value); +#endif +/* TODO: something for LIST */ + +/* + * =========================================================================== + * + * The stuff in the rest of this file should not be used directly. + */ + +#define android_printLog(prio, tag, fmt...) \ + __android_log_print(prio, tag, fmt) + +#define android_vprintLog(prio, cond, tag, fmt...) \ + __android_log_vprint(prio, tag, fmt) + +/* XXX Macros to work around syntax errors in places where format string + * arg is not passed to ALOG_ASSERT, LOG_ALWAYS_FATAL or LOG_ALWAYS_FATAL_IF + * (happens only in debug builds). + */ + +/* Returns 2nd arg. Used to substitute default value if caller's vararg list + * is empty. + */ +#define __android_second(dummy, second, ...) second + +/* If passed multiple args, returns ',' followed by all but 1st arg, otherwise + * returns nothing. + */ +#define __android_rest(first, ...) , ## __VA_ARGS__ + +#define android_printAssert(cond, tag, fmt...) \ + __android_log_assert(cond, tag, \ + __android_second(0, ## fmt, NULL) __android_rest(fmt)) + +#define android_writeLog(prio, tag, text) \ + __android_log_write(prio, tag, text) + +#define android_bWriteLog(tag, payload, len) \ + __android_log_bwrite(tag, payload, len) +#define android_btWriteLog(tag, type, payload, len) \ + __android_log_btwrite(tag, type, payload, len) + +#define android_errorWriteLog(tag, subTag) \ + __android_log_error_write(tag, subTag, -1, NULL, 0) + +#define android_errorWriteWithInfoLog(tag, subTag, uid, data, dataLen) \ + __android_log_error_write(tag, subTag, uid, data, dataLen) + +/* + * IF_ALOG uses android_testLog, but IF_ALOG can be overridden. + * android_testLog will remain constant in its purpose as a wrapper + * for Android logging filter policy, and can be subject to + * change. It can be reused by the developers that override + * IF_ALOG as a convenient means to reimplement their policy + * over Android. + */ +#if LOG_NDEBUG /* Production */ +#define android_testLog(prio, tag) \ + (__android_log_is_loggable(prio, tag, ANDROID_LOG_DEBUG) != 0) +#else +#define android_testLog(prio, tag) \ + (__android_log_is_loggable(prio, tag, ANDROID_LOG_VERBOSE) != 0) +#endif + +// TODO: remove these prototypes and their users +#define android_writevLog(vec,num) do{}while(0) +#define android_write1Log(str,len) do{}while (0) +#define android_setMinPriority(tag, prio) do{}while(0) +//#define android_logToCallback(func) do{}while(0) +#define android_logToFile(tag, file) (0) +#define android_logToFd(tag, fd) (0) + +#ifndef log_id_t_defined +#define log_id_t_defined + +typedef enum log_id { + LOG_ID_MIN = 0, + +#ifndef LINT_RLOG + LOG_ID_MAIN = 0, +#endif + LOG_ID_RADIO = 1, +#ifndef LINT_RLOG + LOG_ID_EVENTS = 2, + LOG_ID_SYSTEM = 3, + LOG_ID_CRASH = 4, + LOG_ID_KERNEL = 5, +#endif + + LOG_ID_MAX +} log_id_t; +#endif +#define sizeof_log_id_t sizeof(typeof_log_id_t) +#define typeof_log_id_t unsigned char + +/* + * Use the per-tag properties "log.tag." to generate a runtime + * result of non-zero to expose a log. + */ +int __android_log_is_loggable(int prio, const char *tag, int def); + +int __android_log_error_write(int tag, const char *subTag, int32_t uid, const char *data, + uint32_t dataLen); + +/* + * Send a simple string to the log. + */ +int __android_log_buf_write(int bufID, int prio, const char *tag, const char *text); +int __android_log_buf_print(int bufID, int prio, const char *tag, const char *fmt, ...) +#if defined(__GNUC__) + __attribute__((__format__(printf, 4, 5))) +#endif + ; + +#ifdef __cplusplus +} +#endif + +#endif /* _LIBS_LOG_LOG_H */ diff --git a/third_party/android_system_core/include/log/log_read.h b/third_party/android_system_core/include/log/log_read.h new file mode 100644 index 00000000000000..1b70affc3540c1 --- /dev/null +++ b/third_party/android_system_core/include/log/log_read.h @@ -0,0 +1,170 @@ +/* + * Copyright (C) 2013-2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_LOG_LOG_READ_H +#define _LIBS_LOG_LOG_READ_H + +#include +#include + +/* struct log_time is a wire-format variant of struct timespec */ +#define NS_PER_SEC 1000000000ULL + +#ifdef __cplusplus + +// NB: do NOT define a copy constructor. This will result in structure +// no longer being compatible with pass-by-value which is desired +// efficient behavior. Also, pass-by-reference breaks C/C++ ABI. +struct log_time { +public: + uint32_t tv_sec; // good to Feb 5 2106 + uint32_t tv_nsec; + + static const uint32_t tv_sec_max = 0xFFFFFFFFUL; + static const uint32_t tv_nsec_max = 999999999UL; + + log_time(const timespec &T) + { + tv_sec = T.tv_sec; + tv_nsec = T.tv_nsec; + } + log_time(uint32_t sec, uint32_t nsec) + { + tv_sec = sec; + tv_nsec = nsec; + } + static const timespec EPOCH; + log_time() + { + } + log_time(clockid_t id) + { + timespec T; + clock_gettime(id, &T); + tv_sec = T.tv_sec; + tv_nsec = T.tv_nsec; + } + log_time(const char *T) + { + const uint8_t *c = (const uint8_t *) T; + tv_sec = c[0] | (c[1] << 8) | (c[2] << 16) | (c[3] << 24); + tv_nsec = c[4] | (c[5] << 8) | (c[6] << 16) | (c[7] << 24); + } + + // timespec + bool operator== (const timespec &T) const + { + return (tv_sec == static_cast(T.tv_sec)) + && (tv_nsec == static_cast(T.tv_nsec)); + } + bool operator!= (const timespec &T) const + { + return !(*this == T); + } + bool operator< (const timespec &T) const + { + return (tv_sec < static_cast(T.tv_sec)) + || ((tv_sec == static_cast(T.tv_sec)) + && (tv_nsec < static_cast(T.tv_nsec))); + } + bool operator>= (const timespec &T) const + { + return !(*this < T); + } + bool operator> (const timespec &T) const + { + return (tv_sec > static_cast(T.tv_sec)) + || ((tv_sec == static_cast(T.tv_sec)) + && (tv_nsec > static_cast(T.tv_nsec))); + } + bool operator<= (const timespec &T) const + { + return !(*this > T); + } + log_time operator-= (const timespec &T); + log_time operator- (const timespec &T) const + { + log_time local(*this); + return local -= T; + } + log_time operator+= (const timespec &T); + log_time operator+ (const timespec &T) const + { + log_time local(*this); + return local += T; + } + + // log_time + bool operator== (const log_time &T) const + { + return (tv_sec == T.tv_sec) && (tv_nsec == T.tv_nsec); + } + bool operator!= (const log_time &T) const + { + return !(*this == T); + } + bool operator< (const log_time &T) const + { + return (tv_sec < T.tv_sec) + || ((tv_sec == T.tv_sec) && (tv_nsec < T.tv_nsec)); + } + bool operator>= (const log_time &T) const + { + return !(*this < T); + } + bool operator> (const log_time &T) const + { + return (tv_sec > T.tv_sec) + || ((tv_sec == T.tv_sec) && (tv_nsec > T.tv_nsec)); + } + bool operator<= (const log_time &T) const + { + return !(*this > T); + } + log_time operator-= (const log_time &T); + log_time operator- (const log_time &T) const + { + log_time local(*this); + return local -= T; + } + log_time operator+= (const log_time &T); + log_time operator+ (const log_time &T) const + { + log_time local(*this); + return local += T; + } + + uint64_t nsec() const + { + return static_cast(tv_sec) * NS_PER_SEC + tv_nsec; + } + + static const char default_format[]; + + // Add %#q for the fraction of a second to the standard library functions + char *strptime(const char *s, const char *format = default_format); +} __attribute__((__packed__)); + +#else + +typedef struct log_time { + uint32_t tv_sec; + uint32_t tv_nsec; +} __attribute__((__packed__)) log_time; + +#endif + +#endif /* define _LIBS_LOG_LOG_READ_H */ diff --git a/third_party/android_system_core/include/log/logd.h b/third_party/android_system_core/include/log/logd.h new file mode 100644 index 00000000000000..0fe515f2abad39 --- /dev/null +++ b/third_party/android_system_core/include/log/logd.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2009 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ANDROID_CUTILS_LOGD_H +#define _ANDROID_CUTILS_LOGD_H + +/* the stable/frozen log-related definitions have been + * moved to this header, which is exposed by the NDK + */ +#include + +/* the rest is only used internally by the system */ +#if !defined(_WIN32) +#include +#endif +#include +#include +#include +#include +#include +#include + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +int __android_log_bwrite(int32_t tag, const void *payload, size_t len); +int __android_log_btwrite(int32_t tag, char type, const void *payload, + size_t len); +int __android_log_bswrite(int32_t tag, const char *payload); + +#ifdef __cplusplus +} +#endif + +#endif /* _LOGD_H */ diff --git a/third_party/android_system_core/include/log/logger.h b/third_party/android_system_core/include/log/logger.h new file mode 100644 index 00000000000000..f030dab5a97d55 --- /dev/null +++ b/third_party/android_system_core/include/log/logger.h @@ -0,0 +1,196 @@ +/* +** +** Copyright 2007-2014, The Android Open Source Project +** +** This file is dual licensed. It may be redistributed and/or modified +** under the terms of the Apache 2.0 License OR version 2 of the GNU +** General Public License. +*/ + +#ifndef _LIBS_LOG_LOGGER_H +#define _LIBS_LOG_LOGGER_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * The userspace structure for version 1 of the logger_entry ABI. + * This structure is returned to userspace by the kernel logger + * driver unless an upgrade to a newer ABI version is requested. + */ +struct logger_entry { + uint16_t len; /* length of the payload */ + uint16_t __pad; /* no matter what, we get 2 bytes of padding */ + int32_t pid; /* generating process's pid */ + int32_t tid; /* generating process's tid */ + int32_t sec; /* seconds since Epoch */ + int32_t nsec; /* nanoseconds */ + char msg[0]; /* the entry's payload */ +} __attribute__((__packed__)); + +/* + * The userspace structure for version 2 of the logger_entry ABI. + * This structure is returned to userspace if ioctl(LOGGER_SET_VERSION) + * is called with version==2; or used with the user space log daemon. + */ +struct logger_entry_v2 { + uint16_t len; /* length of the payload */ + uint16_t hdr_size; /* sizeof(struct logger_entry_v2) */ + int32_t pid; /* generating process's pid */ + int32_t tid; /* generating process's tid */ + int32_t sec; /* seconds since Epoch */ + int32_t nsec; /* nanoseconds */ + uint32_t euid; /* effective UID of logger */ + char msg[0]; /* the entry's payload */ +} __attribute__((__packed__)); + +struct logger_entry_v3 { + uint16_t len; /* length of the payload */ + uint16_t hdr_size; /* sizeof(struct logger_entry_v3) */ + int32_t pid; /* generating process's pid */ + int32_t tid; /* generating process's tid */ + int32_t sec; /* seconds since Epoch */ + int32_t nsec; /* nanoseconds */ + uint32_t lid; /* log id of the payload */ + char msg[0]; /* the entry's payload */ +} __attribute__((__packed__)); + +/* + * The maximum size of the log entry payload that can be + * written to the logger. An attempt to write more than + * this amount will result in a truncated log entry. + */ +#define LOGGER_ENTRY_MAX_PAYLOAD 4076 + +/* + * The maximum size of a log entry which can be read from the + * kernel logger driver. An attempt to read less than this amount + * may result in read() returning EINVAL. + */ +#define LOGGER_ENTRY_MAX_LEN (5*1024) + +#define NS_PER_SEC 1000000000ULL + +struct log_msg { + union { + unsigned char buf[LOGGER_ENTRY_MAX_LEN + 1]; + struct logger_entry_v3 entry; + struct logger_entry_v3 entry_v3; + struct logger_entry_v2 entry_v2; + struct logger_entry entry_v1; + } __attribute__((aligned(4))); +#ifdef __cplusplus + /* Matching log_time operators */ + bool operator== (const log_msg &T) const + { + return (entry.sec == T.entry.sec) && (entry.nsec == T.entry.nsec); + } + bool operator!= (const log_msg &T) const + { + return !(*this == T); + } + bool operator< (const log_msg &T) const + { + return (entry.sec < T.entry.sec) + || ((entry.sec == T.entry.sec) + && (entry.nsec < T.entry.nsec)); + } + bool operator>= (const log_msg &T) const + { + return !(*this < T); + } + bool operator> (const log_msg &T) const + { + return (entry.sec > T.entry.sec) + || ((entry.sec == T.entry.sec) + && (entry.nsec > T.entry.nsec)); + } + bool operator<= (const log_msg &T) const + { + return !(*this > T); + } + uint64_t nsec() const + { + return static_cast(entry.sec) * NS_PER_SEC + entry.nsec; + } + + /* packet methods */ + log_id_t id() + { + return (log_id_t) entry.lid; + } + char *msg() + { + return entry.hdr_size ? (char *) buf + entry.hdr_size : entry_v1.msg; + } + unsigned int len() + { + return (entry.hdr_size ? entry.hdr_size : sizeof(entry_v1)) + entry.len; + } +#endif +}; + +struct logger; + +log_id_t android_logger_get_id(struct logger *logger); + +int android_logger_clear(struct logger *logger); +long android_logger_get_log_size(struct logger *logger); +int android_logger_set_log_size(struct logger *logger, unsigned long size); +long android_logger_get_log_readable_size(struct logger *logger); +int android_logger_get_log_version(struct logger *logger); + +struct logger_list; + +ssize_t android_logger_get_statistics(struct logger_list *logger_list, + char *buf, size_t len); +ssize_t android_logger_get_prune_list(struct logger_list *logger_list, + char *buf, size_t len); +int android_logger_set_prune_list(struct logger_list *logger_list, + char *buf, size_t len); + +#define ANDROID_LOG_RDONLY O_RDONLY +#define ANDROID_LOG_WRONLY O_WRONLY +#define ANDROID_LOG_RDWR O_RDWR +#define ANDROID_LOG_ACCMODE O_ACCMODE +#define ANDROID_LOG_NONBLOCK O_NONBLOCK +#define ANDROID_LOG_PSTORE 0x80000000 + +struct logger_list *android_logger_list_alloc(int mode, + unsigned int tail, + pid_t pid); +struct logger_list *android_logger_list_alloc_time(int mode, + log_time start, + pid_t pid); +void android_logger_list_free(struct logger_list *logger_list); +/* In the purest sense, the following two are orthogonal interfaces */ +int android_logger_list_read(struct logger_list *logger_list, + struct log_msg *log_msg); + +/* Multiple log_id_t opens */ +struct logger *android_logger_open(struct logger_list *logger_list, + log_id_t id); +#define android_logger_close android_logger_free +/* Single log_id_t open */ +struct logger_list *android_logger_list_open(log_id_t id, + int mode, + unsigned int tail, + pid_t pid); +#define android_logger_list_close android_logger_list_free + +/* + * log_id_t helpers + */ +log_id_t android_name_to_log_id(const char *logName); +const char *android_log_id_to_name(log_id_t log_id); + +#ifdef __cplusplus +} +#endif + +#endif /* _LIBS_LOG_LOGGER_H */ diff --git a/third_party/android_system_core/include/log/logprint.h b/third_party/android_system_core/include/log/logprint.h new file mode 100644 index 00000000000000..4b812cc9411d59 --- /dev/null +++ b/third_party/android_system_core/include/log/logprint.h @@ -0,0 +1,161 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LOGPRINT_H +#define _LOGPRINT_H + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum { + FORMAT_OFF = 0, + FORMAT_BRIEF, + FORMAT_PROCESS, + FORMAT_TAG, + FORMAT_THREAD, + FORMAT_RAW, + FORMAT_TIME, + FORMAT_THREADTIME, + FORMAT_LONG, + /* The following three are modifiers to above formats */ + FORMAT_MODIFIER_COLOR, /* converts priority to color */ + FORMAT_MODIFIER_TIME_USEC, /* switches from msec to usec time precision */ + FORMAT_MODIFIER_PRINTABLE, /* converts non-printable to printable escapes */ +} AndroidLogPrintFormat; + +typedef struct AndroidLogFormat_t AndroidLogFormat; + +typedef struct AndroidLogEntry_t { + time_t tv_sec; + long tv_nsec; + android_LogPriority priority; + int32_t pid; + int32_t tid; + const char * tag; + size_t messageLen; + const char * message; +} AndroidLogEntry; + +AndroidLogFormat *android_log_format_new(); + +void android_log_format_free(AndroidLogFormat *p_format); + +/* currently returns 0 if format is a modifier, 1 if not */ +int android_log_setPrintFormat(AndroidLogFormat *p_format, + AndroidLogPrintFormat format); + +/** + * Returns FORMAT_OFF on invalid string + */ +AndroidLogPrintFormat android_log_formatFromString(const char *s); + +/** + * filterExpression: a single filter expression + * eg "AT:d" + * + * returns 0 on success and -1 on invalid expression + * + * Assumes single threaded execution + * + */ + +int android_log_addFilterRule(AndroidLogFormat *p_format, + const char *filterExpression); + + +/** + * filterString: a whitespace-separated set of filter expressions + * eg "AT:d *:i" + * + * returns 0 on success and -1 on invalid expression + * + * Assumes single threaded execution + * + */ + +int android_log_addFilterString(AndroidLogFormat *p_format, + const char *filterString); + + +/** + * returns 1 if this log line should be printed based on its priority + * and tag, and 0 if it should not + */ +int android_log_shouldPrintLine ( + AndroidLogFormat *p_format, const char *tag, android_LogPriority pri); + + +/** + * Splits a wire-format buffer into an AndroidLogEntry + * entry allocated by caller. Pointers will point directly into buf + * + * Returns 0 on success and -1 on invalid wire format (entry will be + * in unspecified state) + */ +int android_log_processLogBuffer(struct logger_entry *buf, + AndroidLogEntry *entry); + +/** + * Like android_log_processLogBuffer, but for binary logs. + * + * If "map" is non-NULL, it will be used to convert the log tag number + * into a string. + */ +int android_log_processBinaryLogBuffer(struct logger_entry *buf, + AndroidLogEntry *entry, const EventTagMap* map, char* messageBuf, + int messageBufLen); + + +/** + * Formats a log message into a buffer + * + * Uses defaultBuffer if it can, otherwise malloc()'s a new buffer + * If return value != defaultBuffer, caller must call free() + * Returns NULL on malloc error + */ + +char *android_log_formatLogLine ( + AndroidLogFormat *p_format, + char *defaultBuffer, + size_t defaultBufferSize, + const AndroidLogEntry *p_line, + size_t *p_outLength); + + +/** + * Either print or do not print log line, based on filter + * + * Assumes single threaded execution + * + */ +int android_log_printLogLine( + AndroidLogFormat *p_format, + int fd, + const AndroidLogEntry *entry); + + +#ifdef __cplusplus +} +#endif + + +#endif /*_LOGPRINT_H*/ diff --git a/third_party/android_system_core/include/log/uio.h b/third_party/android_system_core/include/log/uio.h new file mode 100644 index 00000000000000..7059da5f76942e --- /dev/null +++ b/third_party/android_system_core/include/log/uio.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2007-2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_CUTILS_UIO_H +#define _LIBS_CUTILS_UIO_H + +#if !defined(_WIN32) + +#include + +#else + +#ifdef __cplusplus +extern "C" { +#endif + +// +// Implementation of sys/uio.h for Win32. +// + +#include + +struct iovec { + void* iov_base; + size_t iov_len; +}; + +extern int readv( int fd, struct iovec* vecs, int count ); +extern int writev( int fd, const struct iovec* vecs, int count ); + +#ifdef __cplusplus +} +#endif + +#endif + +#endif /* _LIBS_UTILS_UIO_H */ + diff --git a/third_party/android_system_core/include/system/camera.h b/third_party/android_system_core/include/system/camera.h new file mode 100644 index 00000000000000..0570ca04c6ebe7 --- /dev/null +++ b/third_party/android_system_core/include/system/camera.h @@ -0,0 +1,365 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef SYSTEM_CORE_INCLUDE_ANDROID_CAMERA_H +#define SYSTEM_CORE_INCLUDE_ANDROID_CAMERA_H + +#include +#include +#include +#include +#include +#include + +__BEGIN_DECLS + +/** + * A set of bit masks for specifying how the received preview frames are + * handled before the previewCallback() call. + * + * The least significant 3 bits of an "int" value are used for this purpose: + * + * ..... 0 0 0 + * ^ ^ ^ + * | | |---------> determine whether the callback is enabled or not + * | |-----------> determine whether the callback is one-shot or not + * |-------------> determine whether the frame is copied out or not + * + * WARNING: When a frame is sent directly without copying, it is the frame + * receiver's responsiblity to make sure that the frame data won't get + * corrupted by subsequent preview frames filled by the camera. This flag is + * recommended only when copying out data brings significant performance price + * and the handling/processing of the received frame data is always faster than + * the preview frame rate so that data corruption won't occur. + * + * For instance, + * 1. 0x00 disables the callback. In this case, copy out and one shot bits + * are ignored. + * 2. 0x01 enables a callback without copying out the received frames. A + * typical use case is the Camcorder application to avoid making costly + * frame copies. + * 3. 0x05 is enabling a callback with frame copied out repeatedly. A typical + * use case is the Camera application. + * 4. 0x07 is enabling a callback with frame copied out only once. A typical + * use case is the Barcode scanner application. + */ + +enum { + CAMERA_FRAME_CALLBACK_FLAG_ENABLE_MASK = 0x01, + CAMERA_FRAME_CALLBACK_FLAG_ONE_SHOT_MASK = 0x02, + CAMERA_FRAME_CALLBACK_FLAG_COPY_OUT_MASK = 0x04, + /** Typical use cases */ + CAMERA_FRAME_CALLBACK_FLAG_NOOP = 0x00, + CAMERA_FRAME_CALLBACK_FLAG_CAMCORDER = 0x01, + CAMERA_FRAME_CALLBACK_FLAG_CAMERA = 0x05, + CAMERA_FRAME_CALLBACK_FLAG_BARCODE_SCANNER = 0x07 +}; + +/** msgType in notifyCallback and dataCallback functions */ +enum { + CAMERA_MSG_ERROR = 0x0001, // notifyCallback + CAMERA_MSG_SHUTTER = 0x0002, // notifyCallback + CAMERA_MSG_FOCUS = 0x0004, // notifyCallback + CAMERA_MSG_ZOOM = 0x0008, // notifyCallback + CAMERA_MSG_PREVIEW_FRAME = 0x0010, // dataCallback + CAMERA_MSG_VIDEO_FRAME = 0x0020, // data_timestamp_callback + CAMERA_MSG_POSTVIEW_FRAME = 0x0040, // dataCallback + CAMERA_MSG_RAW_IMAGE = 0x0080, // dataCallback + CAMERA_MSG_COMPRESSED_IMAGE = 0x0100, // dataCallback + CAMERA_MSG_RAW_IMAGE_NOTIFY = 0x0200, // dataCallback + // Preview frame metadata. This can be combined with + // CAMERA_MSG_PREVIEW_FRAME in dataCallback. For example, the apps can + // request FRAME and METADATA. Or the apps can request only FRAME or only + // METADATA. + CAMERA_MSG_PREVIEW_METADATA = 0x0400, // dataCallback + // Notify on autofocus start and stop. This is useful in continuous + // autofocus - FOCUS_MODE_CONTINUOUS_VIDEO and FOCUS_MODE_CONTINUOUS_PICTURE. + CAMERA_MSG_FOCUS_MOVE = 0x0800, // notifyCallback + CAMERA_MSG_VENDOR_START = 0x1000, + CAMERA_MSG_STATS_DATA = CAMERA_MSG_VENDOR_START, + CAMERA_MSG_META_DATA = 0x2000, + CAMERA_MSG_VENDOR_END = 0x8000, + CAMERA_MSG_ALL_MSGS = 0xFFFF +}; + +/** meta data type in CameraMetaDataCallback */ +enum { + CAMERA_META_DATA_ASD = 0x001, //ASD data + CAMERA_META_DATA_FD = 0x002, //FD/FP data + CAMERA_META_DATA_HDR = 0x003, //Auto HDR data +}; + +/** cmdType in sendCommand functions */ +enum { + CAMERA_CMD_START_SMOOTH_ZOOM = 1, + CAMERA_CMD_STOP_SMOOTH_ZOOM = 2, + + /** + * Set the clockwise rotation of preview display (setPreviewDisplay) in + * degrees. This affects the preview frames and the picture displayed after + * snapshot. This method is useful for portrait mode applications. Note + * that preview display of front-facing cameras is flipped horizontally + * before the rotation, that is, the image is reflected along the central + * vertical axis of the camera sensor. So the users can see themselves as + * looking into a mirror. + * + * This does not affect the order of byte array of + * CAMERA_MSG_PREVIEW_FRAME, CAMERA_MSG_VIDEO_FRAME, + * CAMERA_MSG_POSTVIEW_FRAME, CAMERA_MSG_RAW_IMAGE, or + * CAMERA_MSG_COMPRESSED_IMAGE. This is allowed to be set during preview + * since API level 14. + */ + CAMERA_CMD_SET_DISPLAY_ORIENTATION = 3, + + /** + * cmdType to disable/enable shutter sound. In sendCommand passing arg1 = + * 0 will disable, while passing arg1 = 1 will enable the shutter sound. + */ + CAMERA_CMD_ENABLE_SHUTTER_SOUND = 4, + + /* cmdType to play recording sound */ + CAMERA_CMD_PLAY_RECORDING_SOUND = 5, + + /** + * Start the face detection. This should be called after preview is started. + * The camera will notify the listener of CAMERA_MSG_FACE and the detected + * faces in the preview frame. The detected faces may be the same as the + * previous ones. Apps should call CAMERA_CMD_STOP_FACE_DETECTION to stop + * the face detection. This method is supported if CameraParameters + * KEY_MAX_NUM_HW_DETECTED_FACES or KEY_MAX_NUM_SW_DETECTED_FACES is + * bigger than 0. Hardware and software face detection should not be running + * at the same time. If the face detection has started, apps should not send + * this again. + * + * In hardware face detection mode, CameraParameters KEY_WHITE_BALANCE, + * KEY_FOCUS_AREAS and KEY_METERING_AREAS have no effect. + * + * arg1 is the face detection type. It can be CAMERA_FACE_DETECTION_HW or + * CAMERA_FACE_DETECTION_SW. If the type of face detection requested is not + * supported, the HAL must return BAD_VALUE. + */ + CAMERA_CMD_START_FACE_DETECTION = 6, + + /** + * Stop the face detection. + */ + CAMERA_CMD_STOP_FACE_DETECTION = 7, + + /** + * Enable/disable focus move callback (CAMERA_MSG_FOCUS_MOVE). Passing + * arg1 = 0 will disable, while passing arg1 = 1 will enable the callback. + */ + CAMERA_CMD_ENABLE_FOCUS_MOVE_MSG = 8, + + /** + * Ping camera service to see if camera hardware is released. + * + * When any camera method returns error, the client can use ping command + * to see if the camera has been taken away by other clients. If the result + * is NO_ERROR, it means the camera hardware is not released. If the result + * is not NO_ERROR, the camera has been released and the existing client + * can silently finish itself or show a dialog. + */ + CAMERA_CMD_PING = 9, + + /** + * Configure the number of video buffers used for recording. The intended + * video buffer count for recording is passed as arg1, which must be + * greater than 0. This command must be sent before recording is started. + * This command returns INVALID_OPERATION error if it is sent after video + * recording is started, or the command is not supported at all. This + * command also returns a BAD_VALUE error if the intended video buffer + * count is non-positive or too big to be realized. + */ + CAMERA_CMD_SET_VIDEO_BUFFER_COUNT = 10, + + /** + * Configure an explicit format to use for video recording metadata mode. + * This can be used to switch the format from the + * default IMPLEMENTATION_DEFINED gralloc format to some other + * device-supported format, and the default dataspace from the BT_709 color + * space to some other device-supported dataspace. arg1 is the HAL pixel + * format, and arg2 is the HAL dataSpace. This command returns + * INVALID_OPERATION error if it is sent after video recording is started, + * or the command is not supported at all. + * + * If the gralloc format is set to a format other than + * IMPLEMENTATION_DEFINED, then HALv3 devices will use gralloc usage flags + * of SW_READ_OFTEN. + */ +#ifndef CAMERA_VENDOR_L_COMPAT + CAMERA_CMD_SET_VIDEO_FORMAT = 11, + + CAMERA_CMD_VENDOR_START = 20, + /** + * Commands to enable/disable preview histogram + * + * Based on user's input to enable/disable histogram from the camera + * UI, send the appropriate command to the HAL to turn on/off the histogram + * stats and start sending the data to the application. + */ + CAMERA_CMD_HISTOGRAM_ON = CAMERA_CMD_VENDOR_START, + CAMERA_CMD_HISTOGRAM_OFF = CAMERA_CMD_VENDOR_START + 1, + CAMERA_CMD_HISTOGRAM_SEND_DATA = CAMERA_CMD_VENDOR_START + 2, + CAMERA_CMD_LONGSHOT_ON = CAMERA_CMD_VENDOR_START + 3, + CAMERA_CMD_LONGSHOT_OFF = CAMERA_CMD_VENDOR_START + 4, + CAMERA_CMD_STOP_LONGSHOT = CAMERA_CMD_VENDOR_START + 5, + CAMERA_CMD_METADATA_ON = CAMERA_CMD_VENDOR_START + 6, + CAMERA_CMD_METADATA_OFF = CAMERA_CMD_VENDOR_START + 7, + CAMERA_CMD_VENDOR_END = 200, +#else + + /** + * Values used by older HALs, provided as an option for compatibility + */ + CAMERA_CMD_HISTOGRAM_ON = 11, + CAMERA_CMD_HISTOGRAM_OFF = 12, + CAMERA_CMD_HISTOGRAM_SEND_DATA = 13, + CAMERA_CMD_LONGSHOT_ON = 14, + CAMERA_CMD_LONGSHOT_OFF = 15, + CAMERA_CMD_STOP_LONGSHOT = 16, + CAMERA_CMD_METADATA_ON = 100, + CAMERA_CMD_METADATA_OFF = 101, + CAMERA_CMD_SET_VIDEO_FORMAT = 102, +#endif +}; + +/** camera fatal errors */ +enum { + CAMERA_ERROR_UNKNOWN = 1, + /** + * Camera was released because another client has connected to the camera. + * The original client should call Camera::disconnect immediately after + * getting this notification. Otherwise, the camera will be released by + * camera service in a short time. The client should not call any method + * (except disconnect and sending CAMERA_CMD_PING) after getting this. + */ + CAMERA_ERROR_RELEASED = 2, + CAMERA_ERROR_SERVER_DIED = 100 +}; + +enum { + /** The facing of the camera is opposite to that of the screen. */ + CAMERA_FACING_BACK = 0, + /** The facing of the camera is the same as that of the screen. */ + CAMERA_FACING_FRONT = 1, + /** + * The facing of the camera is not fixed relative to the screen. + * The cameras with this facing are external cameras, e.g. USB cameras. + */ + CAMERA_FACING_EXTERNAL = 2 +}; + +enum { + /** Hardware face detection. It does not use much CPU. */ + CAMERA_FACE_DETECTION_HW = 0, + /** + * Software face detection. It uses some CPU. Applications must use + * Camera.setPreviewTexture for preview in this mode. + */ + CAMERA_FACE_DETECTION_SW = 1 +}; + +/** + * The information of a face from camera face detection. + */ +typedef struct camera_face { + /** + * Bounds of the face [left, top, right, bottom]. (-1000, -1000) represents + * the top-left of the camera field of view, and (1000, 1000) represents the + * bottom-right of the field of view. The width and height cannot be 0 or + * negative. This is supported by both hardware and software face detection. + * + * The direction is relative to the sensor orientation, that is, what the + * sensor sees. The direction is not affected by the rotation or mirroring + * of CAMERA_CMD_SET_DISPLAY_ORIENTATION. + */ + int32_t rect[4]; + + /** + * The confidence level of the face. The range is 1 to 100. 100 is the + * highest confidence. This is supported by both hardware and software + * face detection. + */ + int32_t score; + + /** + * An unique id per face while the face is visible to the tracker. If + * the face leaves the field-of-view and comes back, it will get a new + * id. If the value is 0, id is not supported. + */ + int32_t id; + + /** + * The coordinates of the center of the left eye. The range is -1000 to + * 1000. -2000, -2000 if this is not supported. + */ + int32_t left_eye[2]; + + /** + * The coordinates of the center of the right eye. The range is -1000 to + * 1000. -2000, -2000 if this is not supported. + */ + int32_t right_eye[2]; + + /** + * The coordinates of the center of the mouth. The range is -1000 to 1000. + * -2000, -2000 if this is not supported. + */ + int32_t mouth[2]; + int32_t smile_degree; + int32_t smile_score; + int32_t blink_detected; + int32_t face_recognised; + int32_t gaze_angle; + int32_t updown_dir; + int32_t leftright_dir; + int32_t roll_dir; + int32_t left_right_gaze; + int32_t top_bottom_gaze; + int32_t leye_blink; + int32_t reye_blink; + +} camera_face_t; + +/** + * The information of a data type received in a camera frame. + */ +typedef enum { + /** Data buffer */ + CAMERA_FRAME_DATA_BUF = 0x000, + /** File descriptor */ + CAMERA_FRAME_DATA_FD = 0x100 +} camera_frame_data_type_t; + +/** + * The metadata of the frame data. + */ +typedef struct camera_frame_metadata { + /** + * The number of detected faces in the frame. + */ + int32_t number_of_faces; + + /** + * An array of the detected faces. The length is number_of_faces. + */ + camera_face_t *faces; +} camera_frame_metadata_t; + +__END_DECLS + +#endif /* SYSTEM_CORE_INCLUDE_ANDROID_CAMERA_H */ diff --git a/third_party/android_system_core/include/system/graphics.h b/third_party/android_system_core/include/system/graphics.h new file mode 100644 index 00000000000000..afd9f7bdb32f7f --- /dev/null +++ b/third_party/android_system_core/include/system/graphics.h @@ -0,0 +1,763 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef SYSTEM_CORE_INCLUDE_ANDROID_GRAPHICS_H +#define SYSTEM_CORE_INCLUDE_ANDROID_GRAPHICS_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * If the HAL needs to create service threads to handle graphics related + * tasks, these threads need to run at HAL_PRIORITY_URGENT_DISPLAY priority + * if they can block the main rendering thread in any way. + * + * the priority of the current thread can be set with: + * + * #include + * setpriority(PRIO_PROCESS, 0, HAL_PRIORITY_URGENT_DISPLAY); + * + */ + +#define HAL_PRIORITY_URGENT_DISPLAY (-8) + +/** + * pixel format definitions + */ + +enum { + /* + * "linear" color pixel formats: + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer. + * + * The color space determines, for example, if the formats are linear or + * gamma-corrected; or whether any special operations are performed when + * reading or writing into a buffer in one of these formats. + */ + HAL_PIXEL_FORMAT_RGBA_8888 = 1, + HAL_PIXEL_FORMAT_RGBX_8888 = 2, + HAL_PIXEL_FORMAT_RGB_888 = 3, + HAL_PIXEL_FORMAT_RGB_565 = 4, + HAL_PIXEL_FORMAT_BGRA_8888 = 5, + + /* + * 0x100 - 0x1FF + * + * This range is reserved for pixel formats that are specific to the HAL + * implementation. Implementations can use any value in this range to + * communicate video pixel formats between their HAL modules. These formats + * must not have an alpha channel. Additionally, an EGLimage created from a + * gralloc buffer of one of these formats must be supported for use with the + * GL_OES_EGL_image_external OpenGL ES extension. + */ + + /* + * Android YUV format: + * + * This format is exposed outside of the HAL to software decoders and + * applications. EGLImageKHR must support it in conjunction with the + * OES_EGL_image_external extension. + * + * YV12 is a 4:2:0 YCrCb planar format comprised of a WxH Y plane followed + * by (W/2) x (H/2) Cr and Cb planes. + * + * This format assumes + * - an even width + * - an even height + * - a horizontal stride multiple of 16 pixels + * - a vertical stride equal to the height + * + * y_size = stride * height + * c_stride = ALIGN(stride/2, 16) + * c_size = c_stride * height/2 + * size = y_size + c_size * 2 + * cr_offset = y_size + * cb_offset = y_size + c_size + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer. + */ + HAL_PIXEL_FORMAT_YV12 = 0x32315659, // YCrCb 4:2:0 Planar + + + /* + * Android Y8 format: + * + * This format is exposed outside of the HAL to the framework. + * The expected gralloc usage flags are SW_* and HW_CAMERA_*, + * and no other HW_ flags will be used. + * + * Y8 is a YUV planar format comprised of a WxH Y plane, + * with each pixel being represented by 8 bits. + * + * It is equivalent to just the Y plane from YV12. + * + * This format assumes + * - an even width + * - an even height + * - a horizontal stride multiple of 16 pixels + * - a vertical stride equal to the height + * + * size = stride * height + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer. + */ + HAL_PIXEL_FORMAT_Y8 = 0x20203859, + + /* + * Android Y16 format: + * + * This format is exposed outside of the HAL to the framework. + * The expected gralloc usage flags are SW_* and HW_CAMERA_*, + * and no other HW_ flags will be used. + * + * Y16 is a YUV planar format comprised of a WxH Y plane, + * with each pixel being represented by 16 bits. + * + * It is just like Y8, but has double the bits per pixel (little endian). + * + * This format assumes + * - an even width + * - an even height + * - a horizontal stride multiple of 16 pixels + * - a vertical stride equal to the height + * - strides are specified in pixels, not in bytes + * + * size = stride * height * 2 + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer, except that dataSpace field + * HAL_DATASPACE_DEPTH indicates that this buffer contains a depth + * image where each sample is a distance value measured by a depth camera, + * plus an associated confidence value. + */ + HAL_PIXEL_FORMAT_Y16 = 0x20363159, + + /* + * Android RAW sensor format: + * + * This format is exposed outside of the camera HAL to applications. + * + * RAW16 is a single-channel, 16-bit, little endian format, typically + * representing raw Bayer-pattern images from an image sensor, with minimal + * processing. + * + * The exact pixel layout of the data in the buffer is sensor-dependent, and + * needs to be queried from the camera device. + * + * Generally, not all 16 bits are used; more common values are 10 or 12 + * bits. If not all bits are used, the lower-order bits are filled first. + * All parameters to interpret the raw data (black and white points, + * color space, etc) must be queried from the camera device. + * + * This format assumes + * - an even width + * - an even height + * - a horizontal stride multiple of 16 pixels + * - a vertical stride equal to the height + * - strides are specified in pixels, not in bytes + * + * size = stride * height * 2 + * + * This format must be accepted by the gralloc module when used with the + * following usage flags: + * - GRALLOC_USAGE_HW_CAMERA_* + * - GRALLOC_USAGE_SW_* + * - GRALLOC_USAGE_RENDERSCRIPT + * + * When used with ANativeWindow, the dataSpace should be + * HAL_DATASPACE_ARBITRARY, as raw image sensor buffers require substantial + * extra metadata to define. + */ + HAL_PIXEL_FORMAT_RAW16 = 0x20, + + /* + * Android RAW10 format: + * + * This format is exposed outside of the camera HAL to applications. + * + * RAW10 is a single-channel, 10-bit per pixel, densely packed in each row, + * unprocessed format, usually representing raw Bayer-pattern images coming from + * an image sensor. + * + * In an image buffer with this format, starting from the first pixel of each + * row, each 4 consecutive pixels are packed into 5 bytes (40 bits). Each one + * of the first 4 bytes contains the top 8 bits of each pixel, The fifth byte + * contains the 2 least significant bits of the 4 pixels, the exact layout data + * for each 4 consecutive pixels is illustrated below (Pi[j] stands for the jth + * bit of the ith pixel): + * + * bit 7 bit 0 + * =====|=====|=====|=====|=====|=====|=====|=====| + * Byte 0: |P0[9]|P0[8]|P0[7]|P0[6]|P0[5]|P0[4]|P0[3]|P0[2]| + * |-----|-----|-----|-----|-----|-----|-----|-----| + * Byte 1: |P1[9]|P1[8]|P1[7]|P1[6]|P1[5]|P1[4]|P1[3]|P1[2]| + * |-----|-----|-----|-----|-----|-----|-----|-----| + * Byte 2: |P2[9]|P2[8]|P2[7]|P2[6]|P2[5]|P2[4]|P2[3]|P2[2]| + * |-----|-----|-----|-----|-----|-----|-----|-----| + * Byte 3: |P3[9]|P3[8]|P3[7]|P3[6]|P3[5]|P3[4]|P3[3]|P3[2]| + * |-----|-----|-----|-----|-----|-----|-----|-----| + * Byte 4: |P3[1]|P3[0]|P2[1]|P2[0]|P1[1]|P1[0]|P0[1]|P0[0]| + * =============================================== + * + * This format assumes + * - a width multiple of 4 pixels + * - an even height + * - a vertical stride equal to the height + * - strides are specified in bytes, not in pixels + * + * size = stride * height + * + * When stride is equal to width * (10 / 8), there will be no padding bytes at + * the end of each row, the entire image data is densely packed. When stride is + * larger than width * (10 / 8), padding bytes will be present at the end of each + * row (including the last row). + * + * This format must be accepted by the gralloc module when used with the + * following usage flags: + * - GRALLOC_USAGE_HW_CAMERA_* + * - GRALLOC_USAGE_SW_* + * - GRALLOC_USAGE_RENDERSCRIPT + * + * When used with ANativeWindow, the dataSpace field should be + * HAL_DATASPACE_ARBITRARY, as raw image sensor buffers require substantial + * extra metadata to define. + */ + HAL_PIXEL_FORMAT_RAW10 = 0x25, + + /* + * Android RAW12 format: + * + * This format is exposed outside of camera HAL to applications. + * + * RAW12 is a single-channel, 12-bit per pixel, densely packed in each row, + * unprocessed format, usually representing raw Bayer-pattern images coming from + * an image sensor. + * + * In an image buffer with this format, starting from the first pixel of each + * row, each two consecutive pixels are packed into 3 bytes (24 bits). The first + * and second byte contains the top 8 bits of first and second pixel. The third + * byte contains the 4 least significant bits of the two pixels, the exact layout + * data for each two consecutive pixels is illustrated below (Pi[j] stands for + * the jth bit of the ith pixel): + * + * bit 7 bit 0 + * ======|======|======|======|======|======|======|======| + * Byte 0: |P0[11]|P0[10]|P0[ 9]|P0[ 8]|P0[ 7]|P0[ 6]|P0[ 5]|P0[ 4]| + * |------|------|------|------|------|------|------|------| + * Byte 1: |P1[11]|P1[10]|P1[ 9]|P1[ 8]|P1[ 7]|P1[ 6]|P1[ 5]|P1[ 4]| + * |------|------|------|------|------|------|------|------| + * Byte 2: |P1[ 3]|P1[ 2]|P1[ 1]|P1[ 0]|P0[ 3]|P0[ 2]|P0[ 1]|P0[ 0]| + * ======================================================= + * + * This format assumes: + * - a width multiple of 4 pixels + * - an even height + * - a vertical stride equal to the height + * - strides are specified in bytes, not in pixels + * + * size = stride * height + * + * When stride is equal to width * (12 / 8), there will be no padding bytes at + * the end of each row, the entire image data is densely packed. When stride is + * larger than width * (12 / 8), padding bytes will be present at the end of + * each row (including the last row). + * + * This format must be accepted by the gralloc module when used with the + * following usage flags: + * - GRALLOC_USAGE_HW_CAMERA_* + * - GRALLOC_USAGE_SW_* + * - GRALLOC_USAGE_RENDERSCRIPT + * + * When used with ANativeWindow, the dataSpace field should be + * HAL_DATASPACE_ARBITRARY, as raw image sensor buffers require substantial + * extra metadata to define. + */ + HAL_PIXEL_FORMAT_RAW12 = 0x26, + + /* + * Android opaque RAW format: + * + * This format is exposed outside of the camera HAL to applications. + * + * RAW_OPAQUE is a format for unprocessed raw image buffers coming from an + * image sensor. The actual structure of buffers of this format is + * implementation-dependent. + * + * This format must be accepted by the gralloc module when used with the + * following usage flags: + * - GRALLOC_USAGE_HW_CAMERA_* + * - GRALLOC_USAGE_SW_* + * - GRALLOC_USAGE_RENDERSCRIPT + * + * When used with ANativeWindow, the dataSpace field should be + * HAL_DATASPACE_ARBITRARY, as raw image sensor buffers require substantial + * extra metadata to define. + */ + HAL_PIXEL_FORMAT_RAW_OPAQUE = 0x24, + + /* + * Android binary blob graphics buffer format: + * + * This format is used to carry task-specific data which does not have a + * standard image structure. The details of the format are left to the two + * endpoints. + * + * A typical use case is for transporting JPEG-compressed images from the + * Camera HAL to the framework or to applications. + * + * Buffers of this format must have a height of 1, and width equal to their + * size in bytes. + * + * When used with ANativeWindow, the mapping of the dataSpace field to + * buffer contents for BLOB is as follows: + * + * dataSpace value | Buffer contents + * -------------------------------+----------------------------------------- + * HAL_DATASPACE_JFIF | An encoded JPEG image + * HAL_DATASPACE_DEPTH | An android_depth_points buffer + * Other | Unsupported + * + */ + HAL_PIXEL_FORMAT_BLOB = 0x21, + + /* + * Android format indicating that the choice of format is entirely up to the + * device-specific Gralloc implementation. + * + * The Gralloc implementation should examine the usage bits passed in when + * allocating a buffer with this format, and it should derive the pixel + * format from those usage flags. This format will never be used with any + * of the GRALLOC_USAGE_SW_* usage flags. + * + * If a buffer of this format is to be used as an OpenGL ES texture, the + * framework will assume that sampling the texture will always return an + * alpha value of 1.0 (i.e. the buffer contains only opaque pixel values). + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer. + */ + HAL_PIXEL_FORMAT_IMPLEMENTATION_DEFINED = 0x22, + + /* + * Android flexible YCbCr 4:2:0 formats + * + * This format allows platforms to use an efficient YCbCr/YCrCb 4:2:0 + * buffer layout, while still describing the general format in a + * layout-independent manner. While called YCbCr, it can be + * used to describe formats with either chromatic ordering, as well as + * whole planar or semiplanar layouts. + * + * struct android_ycbcr (below) is the the struct used to describe it. + * + * This format must be accepted by the gralloc module when + * USAGE_SW_WRITE_* or USAGE_SW_READ_* are set. + * + * This format is locked for use by gralloc's (*lock_ycbcr) method, and + * locking with the (*lock) method will return an error. + * + * When used with ANativeWindow, the dataSpace field describes the color + * space of the buffer. + */ + HAL_PIXEL_FORMAT_YCbCr_420_888 = 0x23, + + /* + * Android flexible YCbCr 4:2:2 formats + * + * This format allows platforms to use an efficient YCbCr/YCrCb 4:2:2 + * buffer layout, while still describing the general format in a + * layout-independent manner. While called YCbCr, it can be + * used to describe formats with either chromatic ordering, as well as + * whole planar or semiplanar layouts. + * + * This format is currently only used by SW readable buffers + * produced by MediaCodecs, so the gralloc module can ignore this format. + */ + HAL_PIXEL_FORMAT_YCbCr_422_888 = 0x27, + + /* + * Android flexible YCbCr 4:4:4 formats + * + * This format allows platforms to use an efficient YCbCr/YCrCb 4:4:4 + * buffer layout, while still describing the general format in a + * layout-independent manner. While called YCbCr, it can be + * used to describe formats with either chromatic ordering, as well as + * whole planar or semiplanar layouts. + * + * This format is currently only used by SW readable buffers + * produced by MediaCodecs, so the gralloc module can ignore this format. + */ + HAL_PIXEL_FORMAT_YCbCr_444_888 = 0x28, + + /* + * Android flexible RGB 888 formats + * + * This format allows platforms to use an efficient RGB/BGR/RGBX/BGRX + * buffer layout, while still describing the general format in a + * layout-independent manner. While called RGB, it can be + * used to describe formats with either color ordering and optional + * padding, as well as whole planar layout. + * + * This format is currently only used by SW readable buffers + * produced by MediaCodecs, so the gralloc module can ignore this format. + */ + HAL_PIXEL_FORMAT_FLEX_RGB_888 = 0x29, + + /* + * Android flexible RGBA 8888 formats + * + * This format allows platforms to use an efficient RGBA/BGRA/ARGB/ABGR + * buffer layout, while still describing the general format in a + * layout-independent manner. While called RGBA, it can be + * used to describe formats with any of the component orderings, as + * well as whole planar layout. + * + * This format is currently only used by SW readable buffers + * produced by MediaCodecs, so the gralloc module can ignore this format. + */ + HAL_PIXEL_FORMAT_FLEX_RGBA_8888 = 0x2A, + + /* Legacy formats (deprecated), used by ImageFormat.java */ + HAL_PIXEL_FORMAT_YCbCr_422_SP = 0x10, // NV16 + HAL_PIXEL_FORMAT_YCrCb_420_SP = 0x11, // NV21 + HAL_PIXEL_FORMAT_YCbCr_422_I = 0x14, // YUY2 +}; + +/* + * Structure for describing YCbCr formats for consumption by applications. + * This is used with HAL_PIXEL_FORMAT_YCbCr_*_888. + * + * Buffer chroma subsampling is defined in the format. + * e.g. HAL_PIXEL_FORMAT_YCbCr_420_888 has subsampling 4:2:0. + * + * Buffers must have a 8 bit depth. + * + * @y, @cb, and @cr point to the first byte of their respective planes. + * + * Stride describes the distance in bytes from the first value of one row of + * the image to the first value of the next row. It includes the width of the + * image plus padding. + * @ystride is the stride of the luma plane. + * @cstride is the stride of the chroma planes. + * + * @chroma_step is the distance in bytes from one chroma pixel value to the + * next. This is 2 bytes for semiplanar (because chroma values are interleaved + * and each chroma value is one byte) and 1 for planar. + */ + +struct android_ycbcr { + void *y; + void *cb; + void *cr; + size_t ystride; + size_t cstride; + size_t chroma_step; + + /** reserved for future use, set to 0 by gralloc's (*lock_ycbcr)() */ + uint32_t reserved[8]; +}; + +/** + * Structure used to define depth point clouds for format HAL_PIXEL_FORMAT_BLOB + * with dataSpace value of HAL_DATASPACE_DEPTH. + * When locking a native buffer of the above format and dataSpace value, + * the vaddr pointer can be cast to this structure. + * + * A variable-length list of (x,y,z, confidence) 3D points, as floats. (x, y, + * z) represents a measured point's position, with the coordinate system defined + * by the data source. Confidence represents the estimated likelihood that this + * measurement is correct. It is between 0.f and 1.f, inclusive, with 1.f == + * 100% confidence. + * + * @num_points is the number of points in the list + * + * @xyz_points is the flexible array of floating-point values. + * It contains (num_points) * 4 floats. + * + * For example: + * android_depth_points d = get_depth_buffer(); + * struct { + * float x; float y; float z; float confidence; + * } firstPoint, lastPoint; + * + * firstPoint.x = d.xyzc_points[0]; + * firstPoint.y = d.xyzc_points[1]; + * firstPoint.z = d.xyzc_points[2]; + * firstPoint.confidence = d.xyzc_points[3]; + * lastPoint.x = d.xyzc_points[(d.num_points - 1) * 4 + 0]; + * lastPoint.y = d.xyzc_points[(d.num_points - 1) * 4 + 1]; + * lastPoint.z = d.xyzc_points[(d.num_points - 1) * 4 + 2]; + * lastPoint.confidence = d.xyzc_points[(d.num_points - 1) * 4 + 3]; + */ + +struct android_depth_points { + uint32_t num_points; + + /** reserved for future use, set to 0 by gralloc's (*lock)() */ + uint32_t reserved[8]; + + float xyzc_points[]; +}; + +/** + * Transformation definitions + * + * IMPORTANT NOTE: + * HAL_TRANSFORM_ROT_90 is applied CLOCKWISE and AFTER HAL_TRANSFORM_FLIP_{H|V}. + * + */ + +enum { + /* flip source image horizontally (around the vertical axis) */ + HAL_TRANSFORM_FLIP_H = 0x01, + /* flip source image vertically (around the horizontal axis)*/ + HAL_TRANSFORM_FLIP_V = 0x02, + /* rotate source image 90 degrees clockwise */ + HAL_TRANSFORM_ROT_90 = 0x04, + /* rotate source image 180 degrees */ + HAL_TRANSFORM_ROT_180 = 0x03, + /* rotate source image 270 degrees clockwise */ + HAL_TRANSFORM_ROT_270 = 0x07, + /* don't use. see system/window.h */ + HAL_TRANSFORM_RESERVED = 0x08, +}; + +/** + * Dataspace Definitions + * ====================== + * + * Dataspace is the definition of how pixel values should be interpreted. + * + * For many formats, this is the colorspace of the image data, which includes + * primaries (including white point) and the transfer characteristic function, + * which describes both gamma curve and numeric range (within the bit depth). + * + * Other dataspaces include depth measurement data from a depth camera. + */ + +typedef enum android_dataspace { + /* + * Default-assumption data space, when not explicitly specified. + * + * It is safest to assume the buffer is an image with sRGB primaries and + * encoding ranges, but the consumer and/or the producer of the data may + * simply be using defaults. No automatic gamma transform should be + * expected, except for a possible display gamma transform when drawn to a + * screen. + */ + HAL_DATASPACE_UNKNOWN = 0x0, + + /* + * Arbitrary dataspace with manually defined characteristics. Definition + * for colorspaces or other meaning must be communicated separately. + * + * This is used when specifying primaries, transfer characteristics, + * etc. separately. + * + * A typical use case is in video encoding parameters (e.g. for H.264), + * where a colorspace can have separately defined primaries, transfer + * characteristics, etc. + */ + HAL_DATASPACE_ARBITRARY = 0x1, + + /* + * RGB Colorspaces + * ----------------- + * + * Primaries are given using (x,y) coordinates in the CIE 1931 definition + * of x and y specified by ISO 11664-1. + * + * Transfer characteristics are the opto-electronic transfer characteristic + * at the source as a function of linear optical intensity (luminance). + */ + + /* + * sRGB linear encoding: + * + * The red, green, and blue components are stored in sRGB space, but + * are linear, not gamma-encoded. + * The RGB primaries and the white point are the same as BT.709. + * + * The values are encoded using the full range ([0,255] for 8-bit) for all + * components. + */ + HAL_DATASPACE_SRGB_LINEAR = 0x200, + + /* + * sRGB gamma encoding: + * + * The red, green and blue components are stored in sRGB space, and + * converted to linear space when read, using the standard sRGB to linear + * equation: + * + * Clinear = Csrgb / 12.92 for Csrgb <= 0.04045 + * = (Csrgb + 0.055 / 1.055)^2.4 for Csrgb > 0.04045 + * + * When written the inverse transformation is performed: + * + * Csrgb = 12.92 * Clinear for Clinear <= 0.0031308 + * = 1.055 * Clinear^(1/2.4) - 0.055 for Clinear > 0.0031308 + * + * + * The alpha component, if present, is always stored in linear space and + * is left unmodified when read or written. + * + * The RGB primaries and the white point are the same as BT.709. + * + * The values are encoded using the full range ([0,255] for 8-bit) for all + * components. + * + */ + HAL_DATASPACE_SRGB = 0x201, + + /* + * YCbCr Colorspaces + * ----------------- + * + * Primaries are given using (x,y) coordinates in the CIE 1931 definition + * of x and y specified by ISO 11664-1. + * + * Transfer characteristics are the opto-electronic transfer characteristic + * at the source as a function of linear optical intensity (luminance). + */ + + /* + * JPEG File Interchange Format (JFIF) + * + * Same model as BT.601-625, but all values (Y, Cb, Cr) range from 0 to 255 + * + * Transfer characteristic curve: + * E = 1.099 * L ^ 0.45 - 0.099, 1.00 >= L >= 0.018 + * E = 4.500 L, 0.018 > L >= 0 + * L - luminance of image 0 <= L <= 1 for conventional colorimetry + * E - corresponding electrical signal + * + * Primaries: x y + * green 0.290 0.600 + * blue 0.150 0.060 + * red 0.640 0.330 + * white (D65) 0.3127 0.3290 + */ + HAL_DATASPACE_JFIF = 0x101, + + /* + * ITU-R Recommendation 601 (BT.601) - 625-line + * + * Standard-definition television, 625 Lines (PAL) + * + * For 8-bit-depth formats: + * Luma (Y) samples should range from 16 to 235, inclusive + * Chroma (Cb, Cr) samples should range from 16 to 240, inclusive + * + * For 10-bit-depth formats: + * Luma (Y) samples should range from 64 to 940, inclusive + * Chroma (Cb, Cr) samples should range from 64 to 960, inclusive + * + * Transfer characteristic curve: + * E = 1.099 * L ^ 0.45 - 0.099, 1.00 >= L >= 0.018 + * E = 4.500 L, 0.018 > L >= 0 + * L - luminance of image 0 <= L <= 1 for conventional colorimetry + * E - corresponding electrical signal + * + * Primaries: x y + * green 0.290 0.600 + * blue 0.150 0.060 + * red 0.640 0.330 + * white (D65) 0.3127 0.3290 + */ + HAL_DATASPACE_BT601_625 = 0x102, + + /* + * ITU-R Recommendation 601 (BT.601) - 525-line + * + * Standard-definition television, 525 Lines (NTSC) + * + * For 8-bit-depth formats: + * Luma (Y) samples should range from 16 to 235, inclusive + * Chroma (Cb, Cr) samples should range from 16 to 240, inclusive + * + * For 10-bit-depth formats: + * Luma (Y) samples should range from 64 to 940, inclusive + * Chroma (Cb, Cr) samples should range from 64 to 960, inclusive + * + * Transfer characteristic curve: + * E = 1.099 * L ^ 0.45 - 0.099, 1.00 >= L >= 0.018 + * E = 4.500 L, 0.018 > L >= 0 + * L - luminance of image 0 <= L <= 1 for conventional colorimetry + * E - corresponding electrical signal + * + * Primaries: x y + * green 0.310 0.595 + * blue 0.155 0.070 + * red 0.630 0.340 + * white (D65) 0.3127 0.3290 + */ + HAL_DATASPACE_BT601_525 = 0x103, + + /* + * ITU-R Recommendation 709 (BT.709) + * + * High-definition television + * + * For 8-bit-depth formats: + * Luma (Y) samples should range from 16 to 235, inclusive + * Chroma (Cb, Cr) samples should range from 16 to 240, inclusive + * + * For 10-bit-depth formats: + * Luma (Y) samples should range from 64 to 940, inclusive + * Chroma (Cb, Cr) samples should range from 64 to 960, inclusive + * + * Primaries: x y + * green 0.300 0.600 + * blue 0.150 0.060 + * red 0.640 0.330 + * white (D65) 0.3127 0.3290 + */ + HAL_DATASPACE_BT709 = 0x104, + + /* + * The buffer contains depth ranging measurements from a depth camera. + * This value is valid with formats: + * HAL_PIXEL_FORMAT_Y16: 16-bit samples, consisting of a depth measurement + * and an associated confidence value. The 3 MSBs of the sample make + * up the confidence value, and the low 13 LSBs of the sample make up + * the depth measurement. + * For the confidence section, 0 means 100% confidence, 1 means 0% + * confidence. The mapping to a linear float confidence value between + * 0.f and 1.f can be obtained with + * float confidence = (((depthSample >> 13) - 1) & 0x7) / 7.0f; + * The depth measurement can be extracted simply with + * uint16_t range = (depthSample & 0x1FFF); + * HAL_PIXEL_FORMAT_BLOB: A depth point cloud, as + * a variable-length float (x,y,z, confidence) coordinate point list. + * The point cloud will be represented with the android_depth_points + * structure. + */ + HAL_DATASPACE_DEPTH = 0x1000 + +} android_dataspace_t; + +#ifdef __cplusplus +} +#endif + +#endif /* SYSTEM_CORE_INCLUDE_ANDROID_GRAPHICS_H */ diff --git a/third_party/android_system_core/include/system/radio.h b/third_party/android_system_core/include/system/radio.h new file mode 100644 index 00000000000000..a088526046ed1c --- /dev/null +++ b/third_party/android_system_core/include/system/radio.h @@ -0,0 +1,247 @@ +/* + * Copyright (C) 2015 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_RADIO_H +#define ANDROID_RADIO_H + +#include +#include +#include +#include +#include + + +#define RADIO_NUM_BANDS_MAX 16 +#define RADIO_NUM_SPACINGS_MAX 16 +#define RADIO_STRING_LEN_MAX 128 + +/* + * Radio hardware module class. A given radio hardware module HAL is of one class + * only. The platform can not have more than one hardware module of each class. + * Current version of the framework only supports RADIO_CLASS_AM_FM. + */ +typedef enum { + RADIO_CLASS_AM_FM = 0, /* FM (including HD radio) and AM */ + RADIO_CLASS_SAT = 1, /* Satellite Radio */ + RADIO_CLASS_DT = 2, /* Digital Radio (DAB) */ +} radio_class_t; + +/* value for field "type" of radio band described in struct radio_hal_band_config */ +typedef enum { + RADIO_BAND_AM = 0, /* Amplitude Modulation band: LW, MW, SW */ + RADIO_BAND_FM = 1, /* Frequency Modulation band: FM */ + RADIO_BAND_FM_HD = 2, /* FM HD Radio / DRM (IBOC) */ + RADIO_BAND_AM_HD = 3, /* AM HD Radio / DRM (IBOC) */ +} radio_band_t; + +/* RDS variant implemented. A struct radio_hal_fm_band_config can list none or several. */ +enum { + RADIO_RDS_NONE = 0x0, + RADIO_RDS_WORLD = 0x01, + RADIO_RDS_US = 0x02, +}; +typedef unsigned int radio_rds_t; + +/* FM deemphasis variant implemented. A struct radio_hal_fm_band_config can list one or more. */ +enum { + RADIO_DEEMPHASIS_50 = 0x1, + RADIO_DEEMPHASIS_75 = 0x2, +}; +typedef unsigned int radio_deemphasis_t; + +/* Region a particular radio band configuration corresponds to. Not used at the HAL. + * Derived by the framework when converting the band descriptors retrieved from the HAL to + * individual band descriptors for each supported region. */ +typedef enum { + RADIO_REGION_NONE = -1, + RADIO_REGION_ITU_1 = 0, + RADIO_REGION_ITU_2 = 1, + RADIO_REGION_OIRT = 2, + RADIO_REGION_JAPAN = 3, + RADIO_REGION_KOREA = 4, +} radio_region_t; + +/* scanning direction for scan() and step() tuner APIs */ +typedef enum { + RADIO_DIRECTION_UP, + RADIO_DIRECTION_DOWN +} radio_direction_t; + +/* unique handle allocated to a radio module */ +typedef unsigned int radio_handle_t; + +/* Opaque meta data structure used by radio meta data API (see system/radio_metadata.h) */ +typedef struct radio_medtadata radio_metadata_t; + + +/* Additional attributes for an FM band configuration */ +typedef struct radio_hal_fm_band_config { + radio_deemphasis_t deemphasis; /* deemphasis variant */ + bool stereo; /* stereo supported */ + radio_rds_t rds; /* RDS variants supported */ + bool ta; /* Traffic Announcement supported */ + bool af; /* Alternate Frequency supported */ +} radio_hal_fm_band_config_t; + +/* Additional attributes for an AM band configuration */ +typedef struct radio_hal_am_band_config { + bool stereo; /* stereo supported */ +} radio_hal_am_band_config_t; + +/* Radio band configuration. Describes a given band supported by the radio module. + * The HAL can expose only one band per type with the the maximum range supported and all options. + * THe framework will derive the actual regions were this module can operate and expose separate + * band configurations for applications to chose from. */ +typedef struct radio_hal_band_config { + radio_band_t type; + bool antenna_connected; + unsigned int lower_limit; + unsigned int upper_limit; + unsigned int num_spacings; + unsigned int spacings[RADIO_NUM_SPACINGS_MAX]; + union { + radio_hal_fm_band_config_t fm; + radio_hal_am_band_config_t am; + }; +} radio_hal_band_config_t; + +/* Used internally by the framework to represent a band for s specific region */ +typedef struct radio_band_config { + radio_region_t region; + radio_hal_band_config_t band; +} radio_band_config_t; + + +/* Exposes properties of a given hardware radio module. + * NOTE: current framework implementation supports only one audio source (num_audio_sources = 1). + * The source corresponds to AUDIO_DEVICE_IN_FM_TUNER. + * If more than one tuner is supported (num_tuners > 1), only one can be connected to the audio + * source. */ +typedef struct radio_hal_properties { + radio_class_t class_id; /* Class of this module. E.g RADIO_CLASS_AM_FM */ + char implementor[RADIO_STRING_LEN_MAX]; /* implementor name */ + char product[RADIO_STRING_LEN_MAX]; /* product name */ + char version[RADIO_STRING_LEN_MAX]; /* product version */ + char serial[RADIO_STRING_LEN_MAX]; /* serial number (for subscription services) */ + unsigned int num_tuners; /* number of tuners controllable independently */ + unsigned int num_audio_sources; /* number of audio sources driven simultaneously */ + bool supports_capture; /* the hardware supports capture of audio source audio HAL */ + unsigned int num_bands; /* number of band descriptors */ + radio_hal_band_config_t bands[RADIO_NUM_BANDS_MAX]; /* band descriptors */ +} radio_hal_properties_t; + +/* Used internally by the framework. Same information as in struct radio_hal_properties plus a + * unique handle and one band configuration per region. */ +typedef struct radio_properties { + radio_handle_t handle; + radio_class_t class_id; + char implementor[RADIO_STRING_LEN_MAX]; + char product[RADIO_STRING_LEN_MAX]; + char version[RADIO_STRING_LEN_MAX]; + char serial[RADIO_STRING_LEN_MAX]; + unsigned int num_tuners; + unsigned int num_audio_sources; + bool supports_capture; + unsigned int num_bands; + radio_band_config_t bands[RADIO_NUM_BANDS_MAX]; +} radio_properties_t; + +/* Radio program information. Returned by the HAL with event RADIO_EVENT_TUNED. + * Contains information on currently tuned channel. + */ +typedef struct radio_program_info { + unsigned int channel; /* current channel. (e.g kHz for band type RADIO_BAND_FM) */ + unsigned int sub_channel; /* current sub channel. (used for RADIO_BAND_FM_HD) */ + bool tuned; /* tuned to a program or not */ + bool stereo; /* program is stereo or not */ + bool digital; /* digital program or not (e.g HD Radio program) */ + unsigned int signal_strength; /* signal strength from 0 to 100 */ + radio_metadata_t *metadata; /* non null if meta data are present (e.g PTY, song title ...) */ +} radio_program_info_t; + + +/* Events sent to the framework via the HAL callback. An event can notify the completion of an + * asynchronous command (configuration, tune, scan ...) or a spontaneous change (antenna connection, + * failure, AF switching, meta data reception... */ +enum { + RADIO_EVENT_HW_FAILURE = 0, /* hardware module failure. Requires reopening the tuner */ + RADIO_EVENT_CONFIG = 1, /* configuration change completed */ + RADIO_EVENT_ANTENNA = 2, /* Antenna connected, disconnected */ + RADIO_EVENT_TUNED = 3, /* tune, step, scan completed */ + RADIO_EVENT_METADATA = 4, /* New meta data received */ + RADIO_EVENT_TA = 5, /* Traffic announcement start or stop */ + RADIO_EVENT_AF_SWITCH = 6, /* Switch to Alternate Frequency */ + // begin framework only events + RADIO_EVENT_CONTROL = 100, /* loss/gain of tuner control */ + RADIO_EVENT_SERVER_DIED = 101, /* radio service died */ +}; +typedef unsigned int radio_event_type_t; + +/* Event passed to the framework by the HAL callback */ +typedef struct radio_hal_event { + radio_event_type_t type; /* event type */ + int status; /* used by RADIO_EVENT_CONFIG, RADIO_EVENT_TUNED */ + union { + bool on; /* RADIO_EVENT_ANTENNA, RADIO_EVENT_TA */ + radio_hal_band_config_t config; /* RADIO_EVENT_CONFIG */ + radio_program_info_t info; /* RADIO_EVENT_TUNED, RADIO_EVENT_AF_SWITCH */ + radio_metadata_t *metadata; /* RADIO_EVENT_METADATA */ + }; +} radio_hal_event_t; + +/* Used internally by the framework. Same information as in struct radio_hal_event */ +typedef struct radio_event { + radio_event_type_t type; + int status; + union { + bool on; + radio_band_config_t config; + radio_program_info_t info; + radio_metadata_t *metadata; /* offset from start of struct when in shared memory */ + }; +} radio_event_t; + + +static radio_rds_t radio_rds_for_region(bool rds, radio_region_t region) { + if (!rds) + return RADIO_RDS_NONE; + switch(region) { + case RADIO_REGION_ITU_1: + case RADIO_REGION_OIRT: + case RADIO_REGION_JAPAN: + case RADIO_REGION_KOREA: + return RADIO_RDS_WORLD; + case RADIO_REGION_ITU_2: + return RADIO_RDS_US; + default: + return RADIO_REGION_NONE; + } +} + +static radio_deemphasis_t radio_demephasis_for_region(radio_region_t region) { + switch(region) { + case RADIO_REGION_KOREA: + case RADIO_REGION_ITU_2: + return RADIO_DEEMPHASIS_75; + case RADIO_REGION_ITU_1: + case RADIO_REGION_OIRT: + case RADIO_REGION_JAPAN: + default: + return RADIO_DEEMPHASIS_50; + } +} + +#endif // ANDROID_RADIO_H diff --git a/third_party/android_system_core/include/system/thread_defs.h b/third_party/android_system_core/include/system/thread_defs.h new file mode 100644 index 00000000000000..377a48ce922f93 --- /dev/null +++ b/third_party/android_system_core/include/system/thread_defs.h @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_THREAD_DEFS_H +#define ANDROID_THREAD_DEFS_H + +#include "graphics.h" + +#if defined(__cplusplus) +extern "C" { +#endif + +enum { + /* + * *********************************************** + * ** Keep in sync with android.os.Process.java ** + * *********************************************** + * + * This maps directly to the "nice" priorities we use in Android. + * A thread priority should be chosen inverse-proportionally to + * the amount of work the thread is expected to do. The more work + * a thread will do, the less favorable priority it should get so that + * it doesn't starve the system. Threads not behaving properly might + * be "punished" by the kernel. + * Use the levels below when appropriate. Intermediate values are + * acceptable, preferably use the {MORE|LESS}_FAVORABLE constants below. + */ + ANDROID_PRIORITY_LOWEST = 19, + + /* use for background tasks */ + ANDROID_PRIORITY_BACKGROUND = 10, + + /* most threads run at normal priority */ + ANDROID_PRIORITY_NORMAL = 0, + + /* threads currently running a UI that the user is interacting with */ + ANDROID_PRIORITY_FOREGROUND = -2, + + /* the main UI thread has a slightly more favorable priority */ + ANDROID_PRIORITY_DISPLAY = -4, + + /* ui service treads might want to run at a urgent display (uncommon) */ + ANDROID_PRIORITY_URGENT_DISPLAY = HAL_PRIORITY_URGENT_DISPLAY, + + /* all normal audio threads */ + ANDROID_PRIORITY_AUDIO = -16, + + /* service audio threads (uncommon) */ + ANDROID_PRIORITY_URGENT_AUDIO = -19, + + /* should never be used in practice. regular process might not + * be allowed to use this level */ + ANDROID_PRIORITY_HIGHEST = -20, + + ANDROID_PRIORITY_DEFAULT = ANDROID_PRIORITY_NORMAL, + ANDROID_PRIORITY_MORE_FAVORABLE = -1, + ANDROID_PRIORITY_LESS_FAVORABLE = +1, +}; + +#if defined(__cplusplus) +} +#endif + +#endif /* ANDROID_THREAD_DEFS_H */ diff --git a/third_party/android_system_core/include/system/window.h b/third_party/android_system_core/include/system/window.h new file mode 100644 index 00000000000000..508ce00bacecfb --- /dev/null +++ b/third_party/android_system_core/include/system/window.h @@ -0,0 +1,954 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef SYSTEM_CORE_INCLUDE_ANDROID_WINDOW_H +#define SYSTEM_CORE_INCLUDE_ANDROID_WINDOW_H + +#include +#include +#include +#include +#include +#include +#include +#include + +#ifndef __UNUSED +#define __UNUSED __attribute__((__unused__)) +#endif +#ifndef __deprecated +#define __deprecated __attribute__((__deprecated__)) +#endif + +__BEGIN_DECLS + +/*****************************************************************************/ + +#define ANDROID_NATIVE_MAKE_CONSTANT(a,b,c,d) \ + (((unsigned)(a)<<24)|((unsigned)(b)<<16)|((unsigned)(c)<<8)|(unsigned)(d)) + +#define ANDROID_NATIVE_WINDOW_MAGIC \ + ANDROID_NATIVE_MAKE_CONSTANT('_','w','n','d') + +#define ANDROID_NATIVE_BUFFER_MAGIC \ + ANDROID_NATIVE_MAKE_CONSTANT('_','b','f','r') + +// --------------------------------------------------------------------------- + +// This #define may be used to conditionally compile device-specific code to +// support either the prior ANativeWindow interface, which did not pass libsync +// fences around, or the new interface that does. This #define is only present +// when the ANativeWindow interface does include libsync support. +#define ANDROID_NATIVE_WINDOW_HAS_SYNC 1 + +// --------------------------------------------------------------------------- + +typedef const native_handle_t* buffer_handle_t; + +// --------------------------------------------------------------------------- + +typedef struct android_native_rect_t +{ + int32_t left; + int32_t top; + int32_t right; + int32_t bottom; +} android_native_rect_t; + +// --------------------------------------------------------------------------- + +typedef struct android_native_base_t +{ + /* a magic value defined by the actual EGL native type */ + int magic; + + /* the sizeof() of the actual EGL native type */ + int version; + + void* reserved[4]; + + /* reference-counting interface */ + void (*incRef)(struct android_native_base_t* base); + void (*decRef)(struct android_native_base_t* base); +} android_native_base_t; + +typedef struct ANativeWindowBuffer +{ +#ifdef __cplusplus + ANativeWindowBuffer() { + common.magic = ANDROID_NATIVE_BUFFER_MAGIC; + common.version = sizeof(ANativeWindowBuffer); + memset(common.reserved, 0, sizeof(common.reserved)); + } + + // Implement the methods that sp expects so that it + // can be used to automatically refcount ANativeWindowBuffer's. + void incStrong(const void* /*id*/) const { + common.incRef(const_cast(&common)); + } + void decStrong(const void* /*id*/) const { + common.decRef(const_cast(&common)); + } +#endif + + struct android_native_base_t common; + + int width; + int height; + int stride; + int format; + int usage; + + void* reserved[2]; + + buffer_handle_t handle; + + void* reserved_proc[8]; +} ANativeWindowBuffer_t; + +// Old typedef for backwards compatibility. +typedef ANativeWindowBuffer_t android_native_buffer_t; + +// --------------------------------------------------------------------------- + +/* attributes queriable with query() */ +enum { + NATIVE_WINDOW_WIDTH = 0, + NATIVE_WINDOW_HEIGHT = 1, + NATIVE_WINDOW_FORMAT = 2, + + /* The minimum number of buffers that must remain un-dequeued after a buffer + * has been queued. This value applies only if set_buffer_count was used to + * override the number of buffers and if a buffer has since been queued. + * Users of the set_buffer_count ANativeWindow method should query this + * value before calling set_buffer_count. If it is necessary to have N + * buffers simultaneously dequeued as part of the steady-state operation, + * and this query returns M then N+M buffers should be requested via + * native_window_set_buffer_count. + * + * Note that this value does NOT apply until a single buffer has been + * queued. In particular this means that it is possible to: + * + * 1. Query M = min undequeued buffers + * 2. Set the buffer count to N + M + * 3. Dequeue all N + M buffers + * 4. Cancel M buffers + * 5. Queue, dequeue, queue, dequeue, ad infinitum + */ + NATIVE_WINDOW_MIN_UNDEQUEUED_BUFFERS = 3, + + /* Check whether queueBuffer operations on the ANativeWindow send the buffer + * to the window compositor. The query sets the returned 'value' argument + * to 1 if the ANativeWindow DOES send queued buffers directly to the window + * compositor and 0 if the buffers do not go directly to the window + * compositor. + * + * This can be used to determine whether protected buffer content should be + * sent to the ANativeWindow. Note, however, that a result of 1 does NOT + * indicate that queued buffers will be protected from applications or users + * capturing their contents. If that behavior is desired then some other + * mechanism (e.g. the GRALLOC_USAGE_PROTECTED flag) should be used in + * conjunction with this query. + */ + NATIVE_WINDOW_QUEUES_TO_WINDOW_COMPOSER = 4, + + /* Get the concrete type of a ANativeWindow. See below for the list of + * possible return values. + * + * This query should not be used outside the Android framework and will + * likely be removed in the near future. + */ + NATIVE_WINDOW_CONCRETE_TYPE = 5, + + + /* + * Default width and height of ANativeWindow buffers, these are the + * dimensions of the window buffers irrespective of the + * NATIVE_WINDOW_SET_BUFFERS_DIMENSIONS call and match the native window + * size unless overridden by NATIVE_WINDOW_SET_BUFFERS_USER_DIMENSIONS. + */ + NATIVE_WINDOW_DEFAULT_WIDTH = 6, + NATIVE_WINDOW_DEFAULT_HEIGHT = 7, + + /* + * transformation that will most-likely be applied to buffers. This is only + * a hint, the actual transformation applied might be different. + * + * INTENDED USE: + * + * The transform hint can be used by a producer, for instance the GLES + * driver, to pre-rotate the rendering such that the final transformation + * in the composer is identity. This can be very useful when used in + * conjunction with the h/w composer HAL, in situations where it + * cannot handle arbitrary rotations. + * + * 1. Before dequeuing a buffer, the GL driver (or any other ANW client) + * queries the ANW for NATIVE_WINDOW_TRANSFORM_HINT. + * + * 2. The GL driver overrides the width and height of the ANW to + * account for NATIVE_WINDOW_TRANSFORM_HINT. This is done by querying + * NATIVE_WINDOW_DEFAULT_{WIDTH | HEIGHT}, swapping the dimensions + * according to NATIVE_WINDOW_TRANSFORM_HINT and calling + * native_window_set_buffers_dimensions(). + * + * 3. The GL driver dequeues a buffer of the new pre-rotated size. + * + * 4. The GL driver renders to the buffer such that the image is + * already transformed, that is applying NATIVE_WINDOW_TRANSFORM_HINT + * to the rendering. + * + * 5. The GL driver calls native_window_set_transform to apply + * inverse transformation to the buffer it just rendered. + * In order to do this, the GL driver needs + * to calculate the inverse of NATIVE_WINDOW_TRANSFORM_HINT, this is + * done easily: + * + * int hintTransform, inverseTransform; + * query(..., NATIVE_WINDOW_TRANSFORM_HINT, &hintTransform); + * inverseTransform = hintTransform; + * if (hintTransform & HAL_TRANSFORM_ROT_90) + * inverseTransform ^= HAL_TRANSFORM_ROT_180; + * + * + * 6. The GL driver queues the pre-transformed buffer. + * + * 7. The composer combines the buffer transform with the display + * transform. If the buffer transform happens to cancel out the + * display transform then no rotation is needed. + * + */ + NATIVE_WINDOW_TRANSFORM_HINT = 8, + + /* + * Boolean that indicates whether the consumer is running more than + * one buffer behind the producer. + */ + NATIVE_WINDOW_CONSUMER_RUNNING_BEHIND = 9, + + /* + * The consumer gralloc usage bits currently set by the consumer. + * The values are defined in hardware/libhardware/include/gralloc.h. + */ + NATIVE_WINDOW_CONSUMER_USAGE_BITS = 10, + + /** + * Transformation that will by applied to buffers by the hwcomposer. + * This must not be set or checked by producer endpoints, and will + * disable the transform hint set in SurfaceFlinger (see + * NATIVE_WINDOW_TRANSFORM_HINT). + * + * INTENDED USE: + * Temporary - Please do not use this. This is intended only to be used + * by the camera's LEGACY mode. + * + * In situations where a SurfaceFlinger client wishes to set a transform + * that is not visible to the producer, and will always be applied in the + * hardware composer, the client can set this flag with + * native_window_set_buffers_sticky_transform. This can be used to rotate + * and flip buffers consumed by hardware composer without actually changing + * the aspect ratio of the buffers produced. + */ + NATIVE_WINDOW_STICKY_TRANSFORM = 11, + + /** + * The default data space for the buffers as set by the consumer. + * The values are defined in graphics.h. + */ + NATIVE_WINDOW_DEFAULT_DATASPACE = 12, + + /* + * Returns the age of the contents of the most recently dequeued buffer as + * the number of frames that have elapsed since it was last queued. For + * example, if the window is double-buffered, the age of any given buffer in + * steady state will be 2. If the dequeued buffer has never been queued, its + * age will be 0. + */ + NATIVE_WINDOW_BUFFER_AGE = 13, +}; + +/* Valid operations for the (*perform)() hook. + * + * Values marked as 'deprecated' are supported, but have been superceded by + * other functionality. + * + * Values marked as 'private' should be considered private to the framework. + * HAL implementation code with access to an ANativeWindow should not use these, + * as it may not interact properly with the framework's use of the + * ANativeWindow. + */ +enum { + NATIVE_WINDOW_SET_USAGE = 0, + NATIVE_WINDOW_CONNECT = 1, /* deprecated */ + NATIVE_WINDOW_DISCONNECT = 2, /* deprecated */ + NATIVE_WINDOW_SET_CROP = 3, /* private */ + NATIVE_WINDOW_SET_BUFFER_COUNT = 4, + NATIVE_WINDOW_SET_BUFFERS_GEOMETRY = 5, /* deprecated */ + NATIVE_WINDOW_SET_BUFFERS_TRANSFORM = 6, + NATIVE_WINDOW_SET_BUFFERS_TIMESTAMP = 7, + NATIVE_WINDOW_SET_BUFFERS_DIMENSIONS = 8, + NATIVE_WINDOW_SET_BUFFERS_FORMAT = 9, + NATIVE_WINDOW_SET_SCALING_MODE = 10, /* private */ + NATIVE_WINDOW_LOCK = 11, /* private */ + NATIVE_WINDOW_UNLOCK_AND_POST = 12, /* private */ + NATIVE_WINDOW_API_CONNECT = 13, /* private */ + NATIVE_WINDOW_API_DISCONNECT = 14, /* private */ + NATIVE_WINDOW_SET_BUFFERS_USER_DIMENSIONS = 15, /* private */ + NATIVE_WINDOW_SET_POST_TRANSFORM_CROP = 16, /* private */ + NATIVE_WINDOW_SET_BUFFERS_STICKY_TRANSFORM = 17,/* private */ + NATIVE_WINDOW_SET_SIDEBAND_STREAM = 18, + NATIVE_WINDOW_SET_BUFFERS_DATASPACE = 19, + NATIVE_WINDOW_SET_SURFACE_DAMAGE = 20, /* private */ +}; + +/* parameter for NATIVE_WINDOW_[API_][DIS]CONNECT */ +enum { + /* Buffers will be queued by EGL via eglSwapBuffers after being filled using + * OpenGL ES. + */ + NATIVE_WINDOW_API_EGL = 1, + + /* Buffers will be queued after being filled using the CPU + */ + NATIVE_WINDOW_API_CPU = 2, + + /* Buffers will be queued by Stagefright after being filled by a video + * decoder. The video decoder can either be a software or hardware decoder. + */ + NATIVE_WINDOW_API_MEDIA = 3, + + /* Buffers will be queued by the the camera HAL. + */ + NATIVE_WINDOW_API_CAMERA = 4, +}; + +/* parameter for NATIVE_WINDOW_SET_BUFFERS_TRANSFORM */ +enum { + /* flip source image horizontally */ + NATIVE_WINDOW_TRANSFORM_FLIP_H = HAL_TRANSFORM_FLIP_H , + /* flip source image vertically */ + NATIVE_WINDOW_TRANSFORM_FLIP_V = HAL_TRANSFORM_FLIP_V, + /* rotate source image 90 degrees clock-wise, and is applied after TRANSFORM_FLIP_{H|V} */ + NATIVE_WINDOW_TRANSFORM_ROT_90 = HAL_TRANSFORM_ROT_90, + /* rotate source image 180 degrees */ + NATIVE_WINDOW_TRANSFORM_ROT_180 = HAL_TRANSFORM_ROT_180, + /* rotate source image 270 degrees clock-wise */ + NATIVE_WINDOW_TRANSFORM_ROT_270 = HAL_TRANSFORM_ROT_270, + /* transforms source by the inverse transform of the screen it is displayed onto. This + * transform is applied last */ + NATIVE_WINDOW_TRANSFORM_INVERSE_DISPLAY = 0x08 +}; + +/* parameter for NATIVE_WINDOW_SET_SCALING_MODE */ +enum { + /* the window content is not updated (frozen) until a buffer of + * the window size is received (enqueued) + */ + NATIVE_WINDOW_SCALING_MODE_FREEZE = 0, + /* the buffer is scaled in both dimensions to match the window size */ + NATIVE_WINDOW_SCALING_MODE_SCALE_TO_WINDOW = 1, + /* the buffer is scaled uniformly such that the smaller dimension + * of the buffer matches the window size (cropping in the process) + */ + NATIVE_WINDOW_SCALING_MODE_SCALE_CROP = 2, + /* the window is clipped to the size of the buffer's crop rectangle; pixels + * outside the crop rectangle are treated as if they are completely + * transparent. + */ + NATIVE_WINDOW_SCALING_MODE_NO_SCALE_CROP = 3, +}; + +/* values returned by the NATIVE_WINDOW_CONCRETE_TYPE query */ +enum { + NATIVE_WINDOW_FRAMEBUFFER = 0, /* FramebufferNativeWindow */ + NATIVE_WINDOW_SURFACE = 1, /* Surface */ +}; + +/* parameter for NATIVE_WINDOW_SET_BUFFERS_TIMESTAMP + * + * Special timestamp value to indicate that timestamps should be auto-generated + * by the native window when queueBuffer is called. This is equal to INT64_MIN, + * defined directly to avoid problems with C99/C++ inclusion of stdint.h. + */ +static const int64_t NATIVE_WINDOW_TIMESTAMP_AUTO = (-9223372036854775807LL-1); + +struct ANativeWindow +{ +#ifdef __cplusplus + ANativeWindow() + : flags(0), minSwapInterval(0), maxSwapInterval(0), xdpi(0), ydpi(0) + { + common.magic = ANDROID_NATIVE_WINDOW_MAGIC; + common.version = sizeof(ANativeWindow); + memset(common.reserved, 0, sizeof(common.reserved)); + } + + /* Implement the methods that sp expects so that it + can be used to automatically refcount ANativeWindow's. */ + void incStrong(const void* /*id*/) const { + common.incRef(const_cast(&common)); + } + void decStrong(const void* /*id*/) const { + common.decRef(const_cast(&common)); + } +#endif + + struct android_native_base_t common; + + /* flags describing some attributes of this surface or its updater */ + const uint32_t flags; + + /* min swap interval supported by this updated */ + const int minSwapInterval; + + /* max swap interval supported by this updated */ + const int maxSwapInterval; + + /* horizontal and vertical resolution in DPI */ + const float xdpi; + const float ydpi; + + /* Some storage reserved for the OEM's driver. */ + intptr_t oem[4]; + + /* + * Set the swap interval for this surface. + * + * Returns 0 on success or -errno on error. + */ + int (*setSwapInterval)(struct ANativeWindow* window, + int interval); + + /* + * Hook called by EGL to acquire a buffer. After this call, the buffer + * is not locked, so its content cannot be modified. This call may block if + * no buffers are available. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * Returns 0 on success or -errno on error. + * + * XXX: This function is deprecated. It will continue to work for some + * time for binary compatibility, but the new dequeueBuffer function that + * outputs a fence file descriptor should be used in its place. + */ + int (*dequeueBuffer_DEPRECATED)(struct ANativeWindow* window, + struct ANativeWindowBuffer** buffer); + + /* + * hook called by EGL to lock a buffer. This MUST be called before modifying + * the content of a buffer. The buffer must have been acquired with + * dequeueBuffer first. + * + * Returns 0 on success or -errno on error. + * + * XXX: This function is deprecated. It will continue to work for some + * time for binary compatibility, but it is essentially a no-op, and calls + * to it should be removed. + */ + int (*lockBuffer_DEPRECATED)(struct ANativeWindow* window, + struct ANativeWindowBuffer* buffer); + + /* + * Hook called by EGL when modifications to the render buffer are done. + * This unlocks and post the buffer. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * Buffers MUST be queued in the same order than they were dequeued. + * + * Returns 0 on success or -errno on error. + * + * XXX: This function is deprecated. It will continue to work for some + * time for binary compatibility, but the new queueBuffer function that + * takes a fence file descriptor should be used in its place (pass a value + * of -1 for the fence file descriptor if there is no valid one to pass). + */ + int (*queueBuffer_DEPRECATED)(struct ANativeWindow* window, + struct ANativeWindowBuffer* buffer); + + /* + * hook used to retrieve information about the native window. + * + * Returns 0 on success or -errno on error. + */ + int (*query)(const struct ANativeWindow* window, + int what, int* value); + + /* + * hook used to perform various operations on the surface. + * (*perform)() is a generic mechanism to add functionality to + * ANativeWindow while keeping backward binary compatibility. + * + * DO NOT CALL THIS HOOK DIRECTLY. Instead, use the helper functions + * defined below. + * + * (*perform)() returns -ENOENT if the 'what' parameter is not supported + * by the surface's implementation. + * + * See above for a list of valid operations, such as + * NATIVE_WINDOW_SET_USAGE or NATIVE_WINDOW_CONNECT + */ + int (*perform)(struct ANativeWindow* window, + int operation, ... ); + + /* + * Hook used to cancel a buffer that has been dequeued. + * No synchronization is performed between dequeue() and cancel(), so + * either external synchronization is needed, or these functions must be + * called from the same thread. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * XXX: This function is deprecated. It will continue to work for some + * time for binary compatibility, but the new cancelBuffer function that + * takes a fence file descriptor should be used in its place (pass a value + * of -1 for the fence file descriptor if there is no valid one to pass). + */ + int (*cancelBuffer_DEPRECATED)(struct ANativeWindow* window, + struct ANativeWindowBuffer* buffer); + + /* + * Hook called by EGL to acquire a buffer. This call may block if no + * buffers are available. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * The libsync fence file descriptor returned in the int pointed to by the + * fenceFd argument will refer to the fence that must signal before the + * dequeued buffer may be written to. A value of -1 indicates that the + * caller may access the buffer immediately without waiting on a fence. If + * a valid file descriptor is returned (i.e. any value except -1) then the + * caller is responsible for closing the file descriptor. + * + * Returns 0 on success or -errno on error. + */ + int (*dequeueBuffer)(struct ANativeWindow* window, + struct ANativeWindowBuffer** buffer, int* fenceFd); + + /* + * Hook called by EGL when modifications to the render buffer are done. + * This unlocks and post the buffer. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * The fenceFd argument specifies a libsync fence file descriptor for a + * fence that must signal before the buffer can be accessed. If the buffer + * can be accessed immediately then a value of -1 should be used. The + * caller must not use the file descriptor after it is passed to + * queueBuffer, and the ANativeWindow implementation is responsible for + * closing it. + * + * Returns 0 on success or -errno on error. + */ + int (*queueBuffer)(struct ANativeWindow* window, + struct ANativeWindowBuffer* buffer, int fenceFd); + + /* + * Hook used to cancel a buffer that has been dequeued. + * No synchronization is performed between dequeue() and cancel(), so + * either external synchronization is needed, or these functions must be + * called from the same thread. + * + * The window holds a reference to the buffer between dequeueBuffer and + * either queueBuffer or cancelBuffer, so clients only need their own + * reference if they might use the buffer after queueing or canceling it. + * Holding a reference to a buffer after queueing or canceling it is only + * allowed if a specific buffer count has been set. + * + * The fenceFd argument specifies a libsync fence file decsriptor for a + * fence that must signal before the buffer can be accessed. If the buffer + * can be accessed immediately then a value of -1 should be used. + * + * Note that if the client has not waited on the fence that was returned + * from dequeueBuffer, that same fence should be passed to cancelBuffer to + * ensure that future uses of the buffer are preceded by a wait on that + * fence. The caller must not use the file descriptor after it is passed + * to cancelBuffer, and the ANativeWindow implementation is responsible for + * closing it. + * + * Returns 0 on success or -errno on error. + */ + int (*cancelBuffer)(struct ANativeWindow* window, + struct ANativeWindowBuffer* buffer, int fenceFd); +}; + + /* Backwards compatibility: use ANativeWindow (struct ANativeWindow in C). + * android_native_window_t is deprecated. + */ +typedef struct ANativeWindow ANativeWindow; +typedef struct ANativeWindow android_native_window_t __deprecated; + +/* + * native_window_set_usage(..., usage) + * Sets the intended usage flags for the next buffers + * acquired with (*lockBuffer)() and on. + * By default (if this function is never called), a usage of + * GRALLOC_USAGE_HW_RENDER | GRALLOC_USAGE_HW_TEXTURE + * is assumed. + * Calling this function will usually cause following buffers to be + * reallocated. + */ + +static inline int native_window_set_usage( + struct ANativeWindow* window, int usage) +{ + return window->perform(window, NATIVE_WINDOW_SET_USAGE, usage); +} + +/* deprecated. Always returns 0. Don't call. */ +static inline int native_window_connect( + struct ANativeWindow* window __UNUSED, int api __UNUSED) __deprecated; + +static inline int native_window_connect( + struct ANativeWindow* window __UNUSED, int api __UNUSED) { + return 0; +} + +/* deprecated. Always returns 0. Don't call. */ +static inline int native_window_disconnect( + struct ANativeWindow* window __UNUSED, int api __UNUSED) __deprecated; + +static inline int native_window_disconnect( + struct ANativeWindow* window __UNUSED, int api __UNUSED) { + return 0; +} + +/* + * native_window_set_crop(..., crop) + * Sets which region of the next queued buffers needs to be considered. + * Depending on the scaling mode, a buffer's crop region is scaled and/or + * cropped to match the surface's size. This function sets the crop in + * pre-transformed buffer pixel coordinates. + * + * The specified crop region applies to all buffers queued after it is called. + * + * If 'crop' is NULL, subsequently queued buffers won't be cropped. + * + * An error is returned if for instance the crop region is invalid, out of the + * buffer's bound or if the window is invalid. + */ +static inline int native_window_set_crop( + struct ANativeWindow* window, + android_native_rect_t const * crop) +{ + return window->perform(window, NATIVE_WINDOW_SET_CROP, crop); +} + +/* + * native_window_set_post_transform_crop(..., crop) + * Sets which region of the next queued buffers needs to be considered. + * Depending on the scaling mode, a buffer's crop region is scaled and/or + * cropped to match the surface's size. This function sets the crop in + * post-transformed pixel coordinates. + * + * The specified crop region applies to all buffers queued after it is called. + * + * If 'crop' is NULL, subsequently queued buffers won't be cropped. + * + * An error is returned if for instance the crop region is invalid, out of the + * buffer's bound or if the window is invalid. + */ +static inline int native_window_set_post_transform_crop( + struct ANativeWindow* window, + android_native_rect_t const * crop) +{ + return window->perform(window, NATIVE_WINDOW_SET_POST_TRANSFORM_CROP, crop); +} + +/* + * native_window_set_active_rect(..., active_rect) + * + * This function is deprecated and will be removed soon. For now it simply + * sets the post-transform crop for compatibility while multi-project commits + * get checked. + */ +static inline int native_window_set_active_rect( + struct ANativeWindow* window, + android_native_rect_t const * active_rect) __deprecated; + +static inline int native_window_set_active_rect( + struct ANativeWindow* window, + android_native_rect_t const * active_rect) +{ + return native_window_set_post_transform_crop(window, active_rect); +} + +/* + * native_window_set_buffer_count(..., count) + * Sets the number of buffers associated with this native window. + */ +static inline int native_window_set_buffer_count( + struct ANativeWindow* window, + size_t bufferCount) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFER_COUNT, bufferCount); +} + +/* + * native_window_set_buffers_geometry(..., int w, int h, int format) + * All buffers dequeued after this call will have the dimensions and format + * specified. A successful call to this function has the same effect as calling + * native_window_set_buffers_size and native_window_set_buffers_format. + * + * XXX: This function is deprecated. The native_window_set_buffers_dimensions + * and native_window_set_buffers_format functions should be used instead. + */ +static inline int native_window_set_buffers_geometry( + struct ANativeWindow* window, + int w, int h, int format) __deprecated; + +static inline int native_window_set_buffers_geometry( + struct ANativeWindow* window, + int w, int h, int format) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_GEOMETRY, + w, h, format); +} + +/* + * native_window_set_buffers_dimensions(..., int w, int h) + * All buffers dequeued after this call will have the dimensions specified. + * In particular, all buffers will have a fixed-size, independent from the + * native-window size. They will be scaled according to the scaling mode + * (see native_window_set_scaling_mode) upon window composition. + * + * If w and h are 0, the normal behavior is restored. That is, dequeued buffers + * following this call will be sized to match the window's size. + * + * Calling this function will reset the window crop to a NULL value, which + * disables cropping of the buffers. + */ +static inline int native_window_set_buffers_dimensions( + struct ANativeWindow* window, + int w, int h) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_DIMENSIONS, + w, h); +} + +/* + * native_window_set_buffers_user_dimensions(..., int w, int h) + * + * Sets the user buffer size for the window, which overrides the + * window's size. All buffers dequeued after this call will have the + * dimensions specified unless overridden by + * native_window_set_buffers_dimensions. All buffers will have a + * fixed-size, independent from the native-window size. They will be + * scaled according to the scaling mode (see + * native_window_set_scaling_mode) upon window composition. + * + * If w and h are 0, the normal behavior is restored. That is, the + * default buffer size will match the windows's size. + * + * Calling this function will reset the window crop to a NULL value, which + * disables cropping of the buffers. + */ +static inline int native_window_set_buffers_user_dimensions( + struct ANativeWindow* window, + int w, int h) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_USER_DIMENSIONS, + w, h); +} + +/* + * native_window_set_buffers_format(..., int format) + * All buffers dequeued after this call will have the format specified. + * + * If the specified format is 0, the default buffer format will be used. + */ +static inline int native_window_set_buffers_format( + struct ANativeWindow* window, + int format) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_FORMAT, format); +} + +/* + * native_window_set_buffers_data_space(..., int dataSpace) + * All buffers queued after this call will be associated with the dataSpace + * parameter specified. + * + * dataSpace specifies additional information about the buffer that's dependent + * on the buffer format and the endpoints. For example, it can be used to convey + * the color space of the image data in the buffer, or it can be used to + * indicate that the buffers contain depth measurement data instead of color + * images. The default dataSpace is 0, HAL_DATASPACE_UNKNOWN, unless it has been + * overridden by the consumer. + */ +static inline int native_window_set_buffers_data_space( + struct ANativeWindow* window, + android_dataspace_t dataSpace) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_DATASPACE, + dataSpace); +} + +/* + * native_window_set_buffers_transform(..., int transform) + * All buffers queued after this call will be displayed transformed according + * to the transform parameter specified. + */ +static inline int native_window_set_buffers_transform( + struct ANativeWindow* window, + int transform) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_TRANSFORM, + transform); +} + +/* + * native_window_set_buffers_sticky_transform(..., int transform) + * All buffers queued after this call will be displayed transformed according + * to the transform parameter specified applied on top of the regular buffer + * transform. Setting this transform will disable the transform hint. + * + * Temporary - This is only intended to be used by the LEGACY camera mode, do + * not use this for anything else. + */ +static inline int native_window_set_buffers_sticky_transform( + struct ANativeWindow* window, + int transform) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_STICKY_TRANSFORM, + transform); +} + +/* + * native_window_set_buffers_timestamp(..., int64_t timestamp) + * All buffers queued after this call will be associated with the timestamp + * parameter specified. If the timestamp is set to NATIVE_WINDOW_TIMESTAMP_AUTO + * (the default), timestamps will be generated automatically when queueBuffer is + * called. The timestamp is measured in nanoseconds, and is normally monotonically + * increasing. The timestamp should be unaffected by time-of-day adjustments, + * and for a camera should be strictly monotonic but for a media player may be + * reset when the position is set. + */ +static inline int native_window_set_buffers_timestamp( + struct ANativeWindow* window, + int64_t timestamp) +{ + return window->perform(window, NATIVE_WINDOW_SET_BUFFERS_TIMESTAMP, + timestamp); +} + +/* + * native_window_set_scaling_mode(..., int mode) + * All buffers queued after this call will be associated with the scaling mode + * specified. + */ +static inline int native_window_set_scaling_mode( + struct ANativeWindow* window, + int mode) +{ + return window->perform(window, NATIVE_WINDOW_SET_SCALING_MODE, + mode); +} + +/* + * native_window_api_connect(..., int api) + * connects an API to this window. only one API can be connected at a time. + * Returns -EINVAL if for some reason the window cannot be connected, which + * can happen if it's connected to some other API. + */ +static inline int native_window_api_connect( + struct ANativeWindow* window, int api) +{ + return window->perform(window, NATIVE_WINDOW_API_CONNECT, api); +} + +/* + * native_window_api_disconnect(..., int api) + * disconnect the API from this window. + * An error is returned if for instance the window wasn't connected in the + * first place. + */ +static inline int native_window_api_disconnect( + struct ANativeWindow* window, int api) +{ + return window->perform(window, NATIVE_WINDOW_API_DISCONNECT, api); +} + +/* + * native_window_dequeue_buffer_and_wait(...) + * Dequeue a buffer and wait on the fence associated with that buffer. The + * buffer may safely be accessed immediately upon this function returning. An + * error is returned if either of the dequeue or the wait operations fail. + */ +static inline int native_window_dequeue_buffer_and_wait(ANativeWindow *anw, + struct ANativeWindowBuffer** anb) { + return anw->dequeueBuffer_DEPRECATED(anw, anb); +} + +/* + * native_window_set_sideband_stream(..., native_handle_t*) + * Attach a sideband buffer stream to a native window. + */ +static inline int native_window_set_sideband_stream( + struct ANativeWindow* window, + native_handle_t* sidebandHandle) +{ + return window->perform(window, NATIVE_WINDOW_SET_SIDEBAND_STREAM, + sidebandHandle); +} + +/* + * native_window_set_surface_damage(..., android_native_rect_t* rects, int numRects) + * Set the surface damage (i.e., the region of the surface that has changed + * since the previous frame). The damage set by this call will be reset (to the + * default of full-surface damage) after calling queue, so this must be called + * prior to every frame with damage that does not cover the whole surface if the + * caller desires downstream consumers to use this optimization. + * + * The damage region is specified as an array of rectangles, with the important + * caveat that the origin of the surface is considered to be the bottom-left + * corner, as in OpenGL ES. + * + * If numRects is set to 0, rects may be NULL, and the surface damage will be + * set to the full surface (the same as if this function had not been called for + * this frame). + */ +static inline int native_window_set_surface_damage( + struct ANativeWindow* window, + const android_native_rect_t* rects, size_t numRects) +{ + return window->perform(window, NATIVE_WINDOW_SET_SURFACE_DAMAGE, + rects, numRects); +} + +__END_DECLS + +#endif /* SYSTEM_CORE_INCLUDE_ANDROID_WINDOW_H */ diff --git a/third_party/android_system_core/include/utils/AndroidThreads.h b/third_party/android_system_core/include/utils/AndroidThreads.h new file mode 100644 index 00000000000000..aad1e82cb7e439 --- /dev/null +++ b/third_party/android_system_core/include/utils/AndroidThreads.h @@ -0,0 +1,125 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_ANDROID_THREADS_H +#define _LIBS_UTILS_ANDROID_THREADS_H + +#include +#include + +#if !defined(_WIN32) +# include +#endif + +#include + +// --------------------------------------------------------------------------- +// C API + +#ifdef __cplusplus +extern "C" { +#endif + +// Create and run a new thread. +extern int androidCreateThread(android_thread_func_t, void *); + +// Create thread with lots of parameters +extern int androidCreateThreadEtc(android_thread_func_t entryFunction, + void *userData, + const char* threadName, + int32_t threadPriority, + size_t threadStackSize, + android_thread_id_t *threadId); + +// Get some sort of unique identifier for the current thread. +extern android_thread_id_t androidGetThreadId(); + +// Low-level thread creation -- never creates threads that can +// interact with the Java VM. +extern int androidCreateRawThreadEtc(android_thread_func_t entryFunction, + void *userData, + const char* threadName, + int32_t threadPriority, + size_t threadStackSize, + android_thread_id_t *threadId); + +// set the same of the running thread +extern void androidSetThreadName(const char* name); + +// Used by the Java Runtime to control how threads are created, so that +// they can be proper and lovely Java threads. +typedef int (*android_create_thread_fn)(android_thread_func_t entryFunction, + void *userData, + const char* threadName, + int32_t threadPriority, + size_t threadStackSize, + android_thread_id_t *threadId); + +extern void androidSetCreateThreadFunc(android_create_thread_fn func); + +// ------------------------------------------------------------------ +// Extra functions working with raw pids. + +#ifdef HAVE_ANDROID_OS +// Change the priority AND scheduling group of a particular thread. The priority +// should be one of the ANDROID_PRIORITY constants. Returns INVALID_OPERATION +// if the priority set failed, else another value if just the group set failed; +// in either case errno is set. Thread ID zero means current thread. +extern int androidSetThreadPriority(pid_t tid, int prio); + +// Get the current priority of a particular thread. Returns one of the +// ANDROID_PRIORITY constants or a negative result in case of error. +extern int androidGetThreadPriority(pid_t tid); +#endif + +#ifdef __cplusplus +} // extern "C" +#endif + +// ---------------------------------------------------------------------------- +// C++ API +#ifdef __cplusplus +namespace android { +// ---------------------------------------------------------------------------- + +// Create and run a new thread. +inline bool createThread(thread_func_t f, void *a) { + return androidCreateThread(f, a) ? true : false; +} + +// Create thread with lots of parameters +inline bool createThreadEtc(thread_func_t entryFunction, + void *userData, + const char* threadName = "android:unnamed_thread", + int32_t threadPriority = PRIORITY_DEFAULT, + size_t threadStackSize = 0, + thread_id_t *threadId = 0) +{ + return androidCreateThreadEtc(entryFunction, userData, threadName, + threadPriority, threadStackSize, threadId) ? true : false; +} + +// Get some sort of unique identifier for the current thread. +inline thread_id_t getThreadId() { + return androidGetThreadId(); +} + +// ---------------------------------------------------------------------------- +}; // namespace android +#endif // __cplusplus +// ---------------------------------------------------------------------------- + +#endif // _LIBS_UTILS_ANDROID_THREADS_H diff --git a/third_party/android_system_core/include/utils/Atomic.h b/third_party/android_system_core/include/utils/Atomic.h new file mode 100644 index 00000000000000..7eb476c94e106f --- /dev/null +++ b/third_party/android_system_core/include/utils/Atomic.h @@ -0,0 +1,22 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_ATOMIC_H +#define ANDROID_UTILS_ATOMIC_H + +#include + +#endif // ANDROID_UTILS_ATOMIC_H diff --git a/third_party/android_system_core/include/utils/BasicHashtable.h b/third_party/android_system_core/include/utils/BasicHashtable.h new file mode 100644 index 00000000000000..c235d625262651 --- /dev/null +++ b/third_party/android_system_core/include/utils/BasicHashtable.h @@ -0,0 +1,402 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_BASIC_HASHTABLE_H +#define ANDROID_BASIC_HASHTABLE_H + +#include +#include +#include +#include + +namespace android { + +/* Implementation type. Nothing to see here. */ +class BasicHashtableImpl { +protected: + struct Bucket { + // The collision flag indicates that the bucket is part of a collision chain + // such that at least two entries both hash to this bucket. When true, we + // may need to seek further along the chain to find the entry. + static const uint32_t COLLISION = 0x80000000UL; + + // The present flag indicates that the bucket contains an initialized entry value. + static const uint32_t PRESENT = 0x40000000UL; + + // Mask for 30 bits worth of the hash code that are stored within the bucket to + // speed up lookups and rehashing by eliminating the need to recalculate the + // hash code of the entry's key. + static const uint32_t HASH_MASK = 0x3fffffffUL; + + // Combined value that stores the collision and present flags as well as + // a 30 bit hash code. + uint32_t cookie; + + // Storage for the entry begins here. + char entry[0]; + }; + + BasicHashtableImpl(size_t entrySize, bool hasTrivialDestructor, + size_t minimumInitialCapacity, float loadFactor); + BasicHashtableImpl(const BasicHashtableImpl& other); + virtual ~BasicHashtableImpl(); + + void dispose(); + + inline void edit() { + if (mBuckets && !SharedBuffer::bufferFromData(mBuckets)->onlyOwner()) { + clone(); + } + } + + void setTo(const BasicHashtableImpl& other); + void clear(); + + ssize_t next(ssize_t index) const; + ssize_t find(ssize_t index, hash_t hash, const void* __restrict__ key) const; + size_t add(hash_t hash, const void* __restrict__ entry); + void removeAt(size_t index); + void rehash(size_t minimumCapacity, float loadFactor); + + const size_t mBucketSize; // number of bytes per bucket including the entry + const bool mHasTrivialDestructor; // true if the entry type does not require destruction + size_t mCapacity; // number of buckets that can be filled before exceeding load factor + float mLoadFactor; // load factor + size_t mSize; // number of elements actually in the table + size_t mFilledBuckets; // number of buckets for which collision or present is true + size_t mBucketCount; // number of slots in the mBuckets array + void* mBuckets; // array of buckets, as a SharedBuffer + + inline const Bucket& bucketAt(const void* __restrict__ buckets, size_t index) const { + return *reinterpret_cast( + static_cast(buckets) + index * mBucketSize); + } + + inline Bucket& bucketAt(void* __restrict__ buckets, size_t index) const { + return *reinterpret_cast(static_cast(buckets) + index * mBucketSize); + } + + virtual bool compareBucketKey(const Bucket& bucket, const void* __restrict__ key) const = 0; + virtual void initializeBucketEntry(Bucket& bucket, const void* __restrict__ entry) const = 0; + virtual void destroyBucketEntry(Bucket& bucket) const = 0; + +private: + void clone(); + + // Allocates a bucket array as a SharedBuffer. + void* allocateBuckets(size_t count) const; + + // Releases a bucket array's associated SharedBuffer. + void releaseBuckets(void* __restrict__ buckets, size_t count) const; + + // Destroys the contents of buckets (invokes destroyBucketEntry for each + // populated bucket if needed). + void destroyBuckets(void* __restrict__ buckets, size_t count) const; + + // Copies the content of buckets (copies the cookie and invokes copyBucketEntry + // for each populated bucket if needed). + void copyBuckets(const void* __restrict__ fromBuckets, + void* __restrict__ toBuckets, size_t count) const; + + // Determines the appropriate size of a bucket array to store a certain minimum + // number of entries and returns its effective capacity. + static void determineCapacity(size_t minimumCapacity, float loadFactor, + size_t* __restrict__ outBucketCount, size_t* __restrict__ outCapacity); + + // Trim a hash code to 30 bits to match what we store in the bucket's cookie. + inline static hash_t trimHash(hash_t hash) { + return (hash & Bucket::HASH_MASK) ^ (hash >> 30); + } + + // Returns the index of the first bucket that is in the collision chain + // for the specified hash code, given the total number of buckets. + // (Primary hash) + inline static size_t chainStart(hash_t hash, size_t count) { + return hash % count; + } + + // Returns the increment to add to a bucket index to seek to the next bucket + // in the collision chain for the specified hash code, given the total number of buckets. + // (Secondary hash) + inline static size_t chainIncrement(hash_t hash, size_t count) { + return ((hash >> 7) | (hash << 25)) % (count - 1) + 1; + } + + // Returns the index of the next bucket that is in the collision chain + // that is defined by the specified increment, given the total number of buckets. + inline static size_t chainSeek(size_t index, size_t increment, size_t count) { + return (index + increment) % count; + } +}; + +/* + * A BasicHashtable stores entries that are indexed by hash code in place + * within an array. The basic operations are finding entries by key, + * adding new entries and removing existing entries. + * + * This class provides a very limited set of operations with simple semantics. + * It is intended to be used as a building block to construct more complex + * and interesting data structures such as HashMap. Think very hard before + * adding anything extra to BasicHashtable, it probably belongs at a + * higher level of abstraction. + * + * TKey: The key type. + * TEntry: The entry type which is what is actually stored in the array. + * + * TKey must support the following contract: + * bool operator==(const TKey& other) const; // return true if equal + * bool operator!=(const TKey& other) const; // return true if unequal + * + * TEntry must support the following contract: + * const TKey& getKey() const; // get the key from the entry + * + * This class supports storing entries with duplicate keys. Of course, it can't + * tell them apart during removal so only the first entry will be removed. + * We do this because it means that operations like add() can't fail. + */ +template +class BasicHashtable : private BasicHashtableImpl { +public: + /* Creates a hashtable with the specified minimum initial capacity. + * The underlying array will be created when the first entry is added. + * + * minimumInitialCapacity: The minimum initial capacity for the hashtable. + * Default is 0. + * loadFactor: The desired load factor for the hashtable, between 0 and 1. + * Default is 0.75. + */ + BasicHashtable(size_t minimumInitialCapacity = 0, float loadFactor = 0.75f); + + /* Copies a hashtable. + * The underlying storage is shared copy-on-write. + */ + BasicHashtable(const BasicHashtable& other); + + /* Clears and destroys the hashtable. + */ + virtual ~BasicHashtable(); + + /* Making this hashtable a copy of the other hashtable. + * The underlying storage is shared copy-on-write. + * + * other: The hashtable to copy. + */ + inline BasicHashtable& operator =(const BasicHashtable & other) { + setTo(other); + return *this; + } + + /* Returns the number of entries in the hashtable. + */ + inline size_t size() const { + return mSize; + } + + /* Returns the capacity of the hashtable, which is the number of elements that can + * added to the hashtable without requiring it to be grown. + */ + inline size_t capacity() const { + return mCapacity; + } + + /* Returns the number of buckets that the hashtable has, which is the size of its + * underlying array. + */ + inline size_t bucketCount() const { + return mBucketCount; + } + + /* Returns the load factor of the hashtable. */ + inline float loadFactor() const { + return mLoadFactor; + }; + + /* Returns a const reference to the entry at the specified index. + * + * index: The index of the entry to retrieve. Must be a valid index within + * the bounds of the hashtable. + */ + inline const TEntry& entryAt(size_t index) const { + return entryFor(bucketAt(mBuckets, index)); + } + + /* Returns a non-const reference to the entry at the specified index. + * + * index: The index of the entry to edit. Must be a valid index within + * the bounds of the hashtable. + */ + inline TEntry& editEntryAt(size_t index) { + edit(); + return entryFor(bucketAt(mBuckets, index)); + } + + /* Clears the hashtable. + * All entries in the hashtable are destroyed immediately. + * If you need to do something special with the entries in the hashtable then iterate + * over them and do what you need before clearing the hashtable. + */ + inline void clear() { + BasicHashtableImpl::clear(); + } + + /* Returns the index of the next entry in the hashtable given the index of a previous entry. + * If the given index is -1, then returns the index of the first entry in the hashtable, + * if there is one, or -1 otherwise. + * If the given index is not -1, then returns the index of the next entry in the hashtable, + * in strictly increasing order, or -1 if there are none left. + * + * index: The index of the previous entry that was iterated, or -1 to begin + * iteration at the beginning of the hashtable. + */ + inline ssize_t next(ssize_t index) const { + return BasicHashtableImpl::next(index); + } + + /* Finds the index of an entry with the specified key. + * If the given index is -1, then returns the index of the first matching entry, + * otherwise returns the index of the next matching entry. + * If the hashtable contains multiple entries with keys that match the requested + * key, then the sequence of entries returned is arbitrary. + * Returns -1 if no entry was found. + * + * index: The index of the previous entry with the specified key, or -1 to + * find the first matching entry. + * hash: The hashcode of the key. + * key: The key. + */ + inline ssize_t find(ssize_t index, hash_t hash, const TKey& key) const { + return BasicHashtableImpl::find(index, hash, &key); + } + + /* Adds the entry to the hashtable. + * Returns the index of the newly added entry. + * If an entry with the same key already exists, then a duplicate entry is added. + * If the entry will not fit, then the hashtable's capacity is increased and + * its contents are rehashed. See rehash(). + * + * hash: The hashcode of the key. + * entry: The entry to add. + */ + inline size_t add(hash_t hash, const TEntry& entry) { + return BasicHashtableImpl::add(hash, &entry); + } + + /* Removes the entry with the specified index from the hashtable. + * The entry is destroyed immediately. + * The index must be valid. + * + * The hashtable is not compacted after an item is removed, so it is legal + * to continue iterating over the hashtable using next() or find(). + * + * index: The index of the entry to remove. Must be a valid index within the + * bounds of the hashtable, and it must refer to an existing entry. + */ + inline void removeAt(size_t index) { + BasicHashtableImpl::removeAt(index); + } + + /* Rehashes the contents of the hashtable. + * Grows the hashtable to at least the specified minimum capacity or the + * current number of elements, whichever is larger. + * + * Rehashing causes all entries to be copied and the entry indices may change. + * Although the hash codes are cached by the hashtable, rehashing can be an + * expensive operation and should be avoided unless the hashtable's size + * needs to be changed. + * + * Rehashing is the only way to change the capacity or load factor of the + * hashtable once it has been created. It can be used to compact the + * hashtable by choosing a minimum capacity that is smaller than the current + * capacity (such as 0). + * + * minimumCapacity: The desired minimum capacity after rehashing. + * loadFactor: The desired load factor after rehashing. + */ + inline void rehash(size_t minimumCapacity, float loadFactor) { + BasicHashtableImpl::rehash(minimumCapacity, loadFactor); + } + + /* Determines whether there is room to add another entry without rehashing. + * When this returns true, a subsequent add() operation is guaranteed to + * complete without performing a rehash. + */ + inline bool hasMoreRoom() const { + return mCapacity > mFilledBuckets; + } + +protected: + static inline const TEntry& entryFor(const Bucket& bucket) { + return reinterpret_cast(bucket.entry); + } + + static inline TEntry& entryFor(Bucket& bucket) { + return reinterpret_cast(bucket.entry); + } + + virtual bool compareBucketKey(const Bucket& bucket, const void* __restrict__ key) const; + virtual void initializeBucketEntry(Bucket& bucket, const void* __restrict__ entry) const; + virtual void destroyBucketEntry(Bucket& bucket) const; + +private: + // For dumping the raw contents of a hashtable during testing. + friend class BasicHashtableTest; + inline uint32_t cookieAt(size_t index) const { + return bucketAt(mBuckets, index).cookie; + } +}; + +template +BasicHashtable::BasicHashtable(size_t minimumInitialCapacity, float loadFactor) : + BasicHashtableImpl(sizeof(TEntry), traits::has_trivial_dtor, + minimumInitialCapacity, loadFactor) { +} + +template +BasicHashtable::BasicHashtable(const BasicHashtable& other) : + BasicHashtableImpl(other) { +} + +template +BasicHashtable::~BasicHashtable() { + dispose(); +} + +template +bool BasicHashtable::compareBucketKey(const Bucket& bucket, + const void* __restrict__ key) const { + return entryFor(bucket).getKey() == *static_cast(key); +} + +template +void BasicHashtable::initializeBucketEntry(Bucket& bucket, + const void* __restrict__ entry) const { + if (!traits::has_trivial_copy) { + new (&entryFor(bucket)) TEntry(*(static_cast(entry))); + } else { + memcpy(&entryFor(bucket), entry, sizeof(TEntry)); + } +} + +template +void BasicHashtable::destroyBucketEntry(Bucket& bucket) const { + if (!traits::has_trivial_dtor) { + entryFor(bucket).~TEntry(); + } +} + +}; // namespace android + +#endif // ANDROID_BASIC_HASHTABLE_H diff --git a/third_party/android_system_core/include/utils/BitSet.h b/third_party/android_system_core/include/utils/BitSet.h new file mode 100644 index 00000000000000..8c612931de6b65 --- /dev/null +++ b/third_party/android_system_core/include/utils/BitSet.h @@ -0,0 +1,294 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UTILS_BITSET_H +#define UTILS_BITSET_H + +#include +#include + +/* + * Contains some bit manipulation helpers. + */ + +namespace android { + +// A simple set of 32 bits that can be individually marked or cleared. +struct BitSet32 { + uint32_t value; + + inline BitSet32() : value(0UL) { } + explicit inline BitSet32(uint32_t value) : value(value) { } + + // Gets the value associated with a particular bit index. + static inline uint32_t valueForBit(uint32_t n) { return 0x80000000UL >> n; } + + // Clears the bit set. + inline void clear() { clear(value); } + + static inline void clear(uint32_t& value) { value = 0UL; } + + // Returns the number of marked bits in the set. + inline uint32_t count() const { return count(value); } + + static inline uint32_t count(uint32_t value) { return __builtin_popcountl(value); } + + // Returns true if the bit set does not contain any marked bits. + inline bool isEmpty() const { return isEmpty(value); } + + static inline bool isEmpty(uint32_t value) { return ! value; } + + // Returns true if the bit set does not contain any unmarked bits. + inline bool isFull() const { return isFull(value); } + + static inline bool isFull(uint32_t value) { return value == 0xffffffffUL; } + + // Returns true if the specified bit is marked. + inline bool hasBit(uint32_t n) const { return hasBit(value, n); } + + static inline bool hasBit(uint32_t value, uint32_t n) { return value & valueForBit(n); } + + // Marks the specified bit. + inline void markBit(uint32_t n) { markBit(value, n); } + + static inline void markBit (uint32_t& value, uint32_t n) { value |= valueForBit(n); } + + // Clears the specified bit. + inline void clearBit(uint32_t n) { clearBit(value, n); } + + static inline void clearBit(uint32_t& value, uint32_t n) { value &= ~ valueForBit(n); } + + // Finds the first marked bit in the set. + // Result is undefined if all bits are unmarked. + inline uint32_t firstMarkedBit() const { return firstMarkedBit(value); } + + static uint32_t firstMarkedBit(uint32_t value) { return clz_checked(value); } + + // Finds the first unmarked bit in the set. + // Result is undefined if all bits are marked. + inline uint32_t firstUnmarkedBit() const { return firstUnmarkedBit(value); } + + static inline uint32_t firstUnmarkedBit(uint32_t value) { return clz_checked(~ value); } + + // Finds the last marked bit in the set. + // Result is undefined if all bits are unmarked. + inline uint32_t lastMarkedBit() const { return lastMarkedBit(value); } + + static inline uint32_t lastMarkedBit(uint32_t value) { return 31 - ctz_checked(value); } + + // Finds the first marked bit in the set and clears it. Returns the bit index. + // Result is undefined if all bits are unmarked. + inline uint32_t clearFirstMarkedBit() { return clearFirstMarkedBit(value); } + + static inline uint32_t clearFirstMarkedBit(uint32_t& value) { + uint32_t n = firstMarkedBit(value); + clearBit(value, n); + return n; + } + + // Finds the first unmarked bit in the set and marks it. Returns the bit index. + // Result is undefined if all bits are marked. + inline uint32_t markFirstUnmarkedBit() { return markFirstUnmarkedBit(value); } + + static inline uint32_t markFirstUnmarkedBit(uint32_t& value) { + uint32_t n = firstUnmarkedBit(value); + markBit(value, n); + return n; + } + + // Finds the last marked bit in the set and clears it. Returns the bit index. + // Result is undefined if all bits are unmarked. + inline uint32_t clearLastMarkedBit() { return clearLastMarkedBit(value); } + + static inline uint32_t clearLastMarkedBit(uint32_t& value) { + uint32_t n = lastMarkedBit(value); + clearBit(value, n); + return n; + } + + // Gets the index of the specified bit in the set, which is the number of + // marked bits that appear before the specified bit. + inline uint32_t getIndexOfBit(uint32_t n) const { + return getIndexOfBit(value, n); + } + + static inline uint32_t getIndexOfBit(uint32_t value, uint32_t n) { + return __builtin_popcountl(value & ~(0xffffffffUL >> n)); + } + + inline bool operator== (const BitSet32& other) const { return value == other.value; } + inline bool operator!= (const BitSet32& other) const { return value != other.value; } + inline BitSet32 operator& (const BitSet32& other) const { + return BitSet32(value & other.value); + } + inline BitSet32& operator&= (const BitSet32& other) { + value &= other.value; + return *this; + } + inline BitSet32 operator| (const BitSet32& other) const { + return BitSet32(value | other.value); + } + inline BitSet32& operator|= (const BitSet32& other) { + value |= other.value; + return *this; + } + +private: + // We use these helpers as the signature of __builtin_c{l,t}z has "unsigned int" for the + // input, which is only guaranteed to be 16b, not 32. The compiler should optimize this away. + static inline uint32_t clz_checked(uint32_t value) { + if (sizeof(unsigned int) == sizeof(uint32_t)) { + return __builtin_clz(value); + } else { + return __builtin_clzl(value); + } + } + + static inline uint32_t ctz_checked(uint32_t value) { + if (sizeof(unsigned int) == sizeof(uint32_t)) { + return __builtin_ctz(value); + } else { + return __builtin_ctzl(value); + } + } +}; + +ANDROID_BASIC_TYPES_TRAITS(BitSet32) + +// A simple set of 64 bits that can be individually marked or cleared. +struct BitSet64 { + uint64_t value; + + inline BitSet64() : value(0ULL) { } + explicit inline BitSet64(uint64_t value) : value(value) { } + + // Gets the value associated with a particular bit index. + static inline uint64_t valueForBit(uint32_t n) { return 0x8000000000000000ULL >> n; } + + // Clears the bit set. + inline void clear() { clear(value); } + + static inline void clear(uint64_t& value) { value = 0ULL; } + + // Returns the number of marked bits in the set. + inline uint32_t count() const { return count(value); } + + static inline uint32_t count(uint64_t value) { return __builtin_popcountll(value); } + + // Returns true if the bit set does not contain any marked bits. + inline bool isEmpty() const { return isEmpty(value); } + + static inline bool isEmpty(uint64_t value) { return ! value; } + + // Returns true if the bit set does not contain any unmarked bits. + inline bool isFull() const { return isFull(value); } + + static inline bool isFull(uint64_t value) { return value == 0xffffffffffffffffULL; } + + // Returns true if the specified bit is marked. + inline bool hasBit(uint32_t n) const { return hasBit(value, n); } + + static inline bool hasBit(uint64_t value, uint32_t n) { return value & valueForBit(n); } + + // Marks the specified bit. + inline void markBit(uint32_t n) { markBit(value, n); } + + static inline void markBit(uint64_t& value, uint32_t n) { value |= valueForBit(n); } + + // Clears the specified bit. + inline void clearBit(uint32_t n) { clearBit(value, n); } + + static inline void clearBit(uint64_t& value, uint32_t n) { value &= ~ valueForBit(n); } + + // Finds the first marked bit in the set. + // Result is undefined if all bits are unmarked. + inline uint32_t firstMarkedBit() const { return firstMarkedBit(value); } + + static inline uint32_t firstMarkedBit(uint64_t value) { return __builtin_clzll(value); } + + // Finds the first unmarked bit in the set. + // Result is undefined if all bits are marked. + inline uint32_t firstUnmarkedBit() const { return firstUnmarkedBit(value); } + + static inline uint32_t firstUnmarkedBit(uint64_t value) { return __builtin_clzll(~ value); } + + // Finds the last marked bit in the set. + // Result is undefined if all bits are unmarked. + inline uint32_t lastMarkedBit() const { return lastMarkedBit(value); } + + static inline uint32_t lastMarkedBit(uint64_t value) { return 63 - __builtin_ctzll(value); } + + // Finds the first marked bit in the set and clears it. Returns the bit index. + // Result is undefined if all bits are unmarked. + inline uint32_t clearFirstMarkedBit() { return clearFirstMarkedBit(value); } + + static inline uint32_t clearFirstMarkedBit(uint64_t& value) { + uint64_t n = firstMarkedBit(value); + clearBit(value, n); + return n; + } + + // Finds the first unmarked bit in the set and marks it. Returns the bit index. + // Result is undefined if all bits are marked. + inline uint32_t markFirstUnmarkedBit() { return markFirstUnmarkedBit(value); } + + static inline uint32_t markFirstUnmarkedBit(uint64_t& value) { + uint64_t n = firstUnmarkedBit(value); + markBit(value, n); + return n; + } + + // Finds the last marked bit in the set and clears it. Returns the bit index. + // Result is undefined if all bits are unmarked. + inline uint32_t clearLastMarkedBit() { return clearLastMarkedBit(value); } + + static inline uint32_t clearLastMarkedBit(uint64_t& value) { + uint64_t n = lastMarkedBit(value); + clearBit(value, n); + return n; + } + + // Gets the index of the specified bit in the set, which is the number of + // marked bits that appear before the specified bit. + inline uint32_t getIndexOfBit(uint32_t n) const { return getIndexOfBit(value, n); } + + static inline uint32_t getIndexOfBit(uint64_t value, uint32_t n) { + return __builtin_popcountll(value & ~(0xffffffffffffffffULL >> n)); + } + + inline bool operator== (const BitSet64& other) const { return value == other.value; } + inline bool operator!= (const BitSet64& other) const { return value != other.value; } + inline BitSet64 operator& (const BitSet64& other) const { + return BitSet64(value & other.value); + } + inline BitSet64& operator&= (const BitSet64& other) { + value &= other.value; + return *this; + } + inline BitSet64 operator| (const BitSet64& other) const { + return BitSet64(value | other.value); + } + inline BitSet64& operator|= (const BitSet64& other) { + value |= other.value; + return *this; + } +}; + +ANDROID_BASIC_TYPES_TRAITS(BitSet64) + +} // namespace android + +#endif // UTILS_BITSET_H diff --git a/third_party/android_system_core/include/utils/BlobCache.h b/third_party/android_system_core/include/utils/BlobCache.h new file mode 100644 index 00000000000000..65dca9fb4583fa --- /dev/null +++ b/third_party/android_system_core/include/utils/BlobCache.h @@ -0,0 +1,249 @@ +/* + ** Copyright 2011, The Android Open Source Project + ** + ** Licensed under the Apache License, Version 2.0 (the "License"); + ** you may not use this file except in compliance with the License. + ** You may obtain a copy of the License at + ** + ** http://www.apache.org/licenses/LICENSE-2.0 + ** + ** Unless required by applicable law or agreed to in writing, software + ** distributed under the License is distributed on an "AS IS" BASIS, + ** WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + ** See the License for the specific language governing permissions and + ** limitations under the License. + */ + +#ifndef ANDROID_BLOB_CACHE_H +#define ANDROID_BLOB_CACHE_H + +#include + +#include +#include +#include +#include + +namespace android { + +// A BlobCache is an in-memory cache for binary key/value pairs. A BlobCache +// does NOT provide any thread-safety guarantees. +// +// The cache contents can be serialized to an in-memory buffer or mmap'd file +// and then reloaded in a subsequent execution of the program. This +// serialization is non-portable and the data should only be used by the device +// that generated it. +class BlobCache : public RefBase { + +public: + + // Create an empty blob cache. The blob cache will cache key/value pairs + // with key and value sizes less than or equal to maxKeySize and + // maxValueSize, respectively. The total combined size of ALL cache entries + // (key sizes plus value sizes) will not exceed maxTotalSize. + BlobCache(size_t maxKeySize, size_t maxValueSize, size_t maxTotalSize); + + // set inserts a new binary value into the cache and associates it with the + // given binary key. If the key or value are too large for the cache then + // the cache remains unchanged. This includes the case where a different + // value was previously associated with the given key - the old value will + // remain in the cache. If the given key and value are small enough to be + // put in the cache (based on the maxKeySize, maxValueSize, and maxTotalSize + // values specified to the BlobCache constructor), then the key/value pair + // will be in the cache after set returns. Note, however, that a subsequent + // call to set may evict old key/value pairs from the cache. + // + // Preconditions: + // key != NULL + // 0 < keySize + // value != NULL + // 0 < valueSize + void set(const void* key, size_t keySize, const void* value, + size_t valueSize); + + // get retrieves from the cache the binary value associated with a given + // binary key. If the key is present in the cache then the length of the + // binary value associated with that key is returned. If the value argument + // is non-NULL and the size of the cached value is less than valueSize bytes + // then the cached value is copied into the buffer pointed to by the value + // argument. If the key is not present in the cache then 0 is returned and + // the buffer pointed to by the value argument is not modified. + // + // Note that when calling get multiple times with the same key, the later + // calls may fail, returning 0, even if earlier calls succeeded. The return + // value must be checked for each call. + // + // Preconditions: + // key != NULL + // 0 < keySize + // 0 <= valueSize + size_t get(const void* key, size_t keySize, void* value, size_t valueSize); + + + // getFlattenedSize returns the number of bytes needed to store the entire + // serialized cache. + size_t getFlattenedSize() const; + + // flatten serializes the current contents of the cache into the memory + // pointed to by 'buffer'. The serialized cache contents can later be + // loaded into a BlobCache object using the unflatten method. The contents + // of the BlobCache object will not be modified. + // + // Preconditions: + // size >= this.getFlattenedSize() + status_t flatten(void* buffer, size_t size) const; + + // unflatten replaces the contents of the cache with the serialized cache + // contents in the memory pointed to by 'buffer'. The previous contents of + // the BlobCache will be evicted from the cache. If an error occurs while + // unflattening the serialized cache contents then the BlobCache will be + // left in an empty state. + // + status_t unflatten(void const* buffer, size_t size); + +private: + // Copying is disallowed. + BlobCache(const BlobCache&); + void operator=(const BlobCache&); + + // A random function helper to get around MinGW not having nrand48() + long int blob_random(); + + // clean evicts a randomly chosen set of entries from the cache such that + // the total size of all remaining entries is less than mMaxTotalSize/2. + void clean(); + + // isCleanable returns true if the cache is full enough for the clean method + // to have some effect, and false otherwise. + bool isCleanable() const; + + // A Blob is an immutable sized unstructured data blob. + class Blob : public RefBase { + public: + Blob(const void* data, size_t size, bool copyData); + ~Blob(); + + bool operator<(const Blob& rhs) const; + + const void* getData() const; + size_t getSize() const; + + private: + // Copying is not allowed. + Blob(const Blob&); + void operator=(const Blob&); + + // mData points to the buffer containing the blob data. + const void* mData; + + // mSize is the size of the blob data in bytes. + size_t mSize; + + // mOwnsData indicates whether or not this Blob object should free the + // memory pointed to by mData when the Blob gets destructed. + bool mOwnsData; + }; + + // A CacheEntry is a single key/value pair in the cache. + class CacheEntry { + public: + CacheEntry(); + CacheEntry(const sp& key, const sp& value); + CacheEntry(const CacheEntry& ce); + + bool operator<(const CacheEntry& rhs) const; + const CacheEntry& operator=(const CacheEntry&); + + sp getKey() const; + sp getValue() const; + + void setValue(const sp& value); + + private: + + // mKey is the key that identifies the cache entry. + sp mKey; + + // mValue is the cached data associated with the key. + sp mValue; + }; + + // A Header is the header for the entire BlobCache serialization format. No + // need to make this portable, so we simply write the struct out. + struct Header { + // mMagicNumber is the magic number that identifies the data as + // serialized BlobCache contents. It must always contain 'Blb$'. + uint32_t mMagicNumber; + + // mBlobCacheVersion is the serialization format version. + uint32_t mBlobCacheVersion; + + // mDeviceVersion is the device-specific version of the cache. This can + // be used to invalidate the cache. + uint32_t mDeviceVersion; + + // mNumEntries is number of cache entries following the header in the + // data. + size_t mNumEntries; + + // mBuildId is the build id of the device when the cache was created. + // When an update to the build happens (via an OTA or other update) this + // is used to invalidate the cache. + int mBuildIdLength; + char mBuildId[]; + }; + + // An EntryHeader is the header for a serialized cache entry. No need to + // make this portable, so we simply write the struct out. Each EntryHeader + // is followed imediately by the key data and then the value data. + // + // The beginning of each serialized EntryHeader is 4-byte aligned, so the + // number of bytes that a serialized cache entry will occupy is: + // + // ((sizeof(EntryHeader) + keySize + valueSize) + 3) & ~3 + // + struct EntryHeader { + // mKeySize is the size of the entry key in bytes. + size_t mKeySize; + + // mValueSize is the size of the entry value in bytes. + size_t mValueSize; + + // mData contains both the key and value data for the cache entry. The + // key comes first followed immediately by the value. + uint8_t mData[]; + }; + + // mMaxKeySize is the maximum key size that will be cached. Calls to + // BlobCache::set with a keySize parameter larger than mMaxKeySize will + // simply not add the key/value pair to the cache. + const size_t mMaxKeySize; + + // mMaxValueSize is the maximum value size that will be cached. Calls to + // BlobCache::set with a valueSize parameter larger than mMaxValueSize will + // simply not add the key/value pair to the cache. + const size_t mMaxValueSize; + + // mMaxTotalSize is the maximum size that all cache entries can occupy. This + // includes space for both keys and values. When a call to BlobCache::set + // would otherwise cause this limit to be exceeded, either the key/value + // pair passed to BlobCache::set will not be cached or other cache entries + // will be evicted from the cache to make room for the new entry. + const size_t mMaxTotalSize; + + // mTotalSize is the total combined size of all keys and values currently in + // the cache. + size_t mTotalSize; + + // mRandState is the pseudo-random number generator state. It is passed to + // nrand48 to generate random numbers when needed. + unsigned short mRandState[3]; + + // mCacheEntries stores all the cache entries that are resident in memory. + // Cache entries are added to it by the 'set' method. + SortedVector mCacheEntries; +}; + +} + +#endif // ANDROID_BLOB_CACHE_H diff --git a/third_party/android_system_core/include/utils/ByteOrder.h b/third_party/android_system_core/include/utils/ByteOrder.h new file mode 100644 index 00000000000000..baa3a83dddfc47 --- /dev/null +++ b/third_party/android_system_core/include/utils/ByteOrder.h @@ -0,0 +1,81 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// + +#ifndef _LIBS_UTILS_BYTE_ORDER_H +#define _LIBS_UTILS_BYTE_ORDER_H + +#include +#include +#ifdef HAVE_WINSOCK +#include +#else +#include +#endif + +/* + * These macros are like the hton/ntoh byte swapping macros, + * except they allow you to swap to and from the "device" byte + * order. The device byte order is the endianness of the target + * device -- for the ARM CPUs we use today, this is little endian. + * + * Note that the byte swapping functions have not been optimized + * much; performance is currently not an issue for them since the + * intent is to allow us to avoid byte swapping on the device. + */ + +static inline uint32_t android_swap_long(uint32_t v) +{ + return (v<<24) | ((v<<8)&0x00FF0000) | ((v>>8)&0x0000FF00) | (v>>24); +} + +static inline uint16_t android_swap_short(uint16_t v) +{ + return (v<<8) | (v>>8); +} + +#define DEVICE_BYTE_ORDER LITTLE_ENDIAN + +#if BYTE_ORDER == DEVICE_BYTE_ORDER + +#define dtohl(x) (x) +#define dtohs(x) (x) +#define htodl(x) (x) +#define htods(x) (x) + +#else + +#define dtohl(x) (android_swap_long(x)) +#define dtohs(x) (android_swap_short(x)) +#define htodl(x) (android_swap_long(x)) +#define htods(x) (android_swap_short(x)) + +#endif + +#if BYTE_ORDER == LITTLE_ENDIAN +#define fromlel(x) (x) +#define fromles(x) (x) +#define tolel(x) (x) +#define toles(x) (x) +#else +#define fromlel(x) (android_swap_long(x)) +#define fromles(x) (android_swap_short(x)) +#define tolel(x) (android_swap_long(x)) +#define toles(x) (android_swap_short(x)) +#endif + +#endif // _LIBS_UTILS_BYTE_ORDER_H diff --git a/third_party/android_system_core/include/utils/CallStack.h b/third_party/android_system_core/include/utils/CallStack.h new file mode 100644 index 00000000000000..27e89f4622c8dc --- /dev/null +++ b/third_party/android_system_core/include/utils/CallStack.h @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_CALLSTACK_H +#define ANDROID_CALLSTACK_H + +#include +#include +#include +#include + +#include +#include + +namespace android { + +class Printer; + +// Collect/print the call stack (function, file, line) traces for a single thread. +class CallStack { +public: + // Create an empty call stack. No-op. + CallStack(); + // Create a callstack with the current thread's stack trace. + // Immediately dump it to logcat using the given logtag. + CallStack(const char* logtag, int32_t ignoreDepth=1); + ~CallStack(); + + // Reset the stack frames (same as creating an empty call stack). + void clear() { mFrameLines.clear(); } + + // Immediately collect the stack traces for the specified thread. + // The default is to dump the stack of the current call. + void update(int32_t ignoreDepth=1, pid_t tid=BACKTRACE_CURRENT_THREAD); + + // Dump a stack trace to the log using the supplied logtag. + void log(const char* logtag, + android_LogPriority priority = ANDROID_LOG_DEBUG, + const char* prefix = 0) const; + + // Dump a stack trace to the specified file descriptor. + void dump(int fd, int indent = 0, const char* prefix = 0) const; + + // Return a string (possibly very long) containing the complete stack trace. + String8 toString(const char* prefix = 0) const; + + // Dump a serialized representation of the stack trace to the specified printer. + void print(Printer& printer) const; + + // Get the count of stack frames that are in this call stack. + size_t size() const { return mFrameLines.size(); } + +private: + Vector mFrameLines; +}; + +}; // namespace android + +#endif // ANDROID_CALLSTACK_H diff --git a/third_party/android_system_core/include/utils/Compat.h b/third_party/android_system_core/include/utils/Compat.h new file mode 100644 index 00000000000000..7d96310272e117 --- /dev/null +++ b/third_party/android_system_core/include/utils/Compat.h @@ -0,0 +1,78 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __LIB_UTILS_COMPAT_H +#define __LIB_UTILS_COMPAT_H + +#include + +#if defined(__APPLE__) + +/* Mac OS has always had a 64-bit off_t, so it doesn't have off64_t. */ + +typedef off_t off64_t; + +static inline off64_t lseek64(int fd, off64_t offset, int whence) { + return lseek(fd, offset, whence); +} + +static inline ssize_t pread64(int fd, void* buf, size_t nbytes, off64_t offset) { + return pread(fd, buf, nbytes, offset); +} + +#endif /* __APPLE__ */ + +#if defined(_WIN32) +#define O_CLOEXEC O_NOINHERIT +#define O_NOFOLLOW 0 +#define DEFFILEMODE 0666 +#endif /* _WIN32 */ + +#if defined(_WIN32) +#define ZD "%ld" +#define ZD_TYPE long +#else +#define ZD "%zd" +#define ZD_TYPE ssize_t +#endif + +/* + * Needed for cases where something should be constexpr if possible, but not + * being constexpr is fine if in pre-C++11 code (such as a const static float + * member variable). + */ +#if __cplusplus >= 201103L +#define CONSTEXPR constexpr +#else +#define CONSTEXPR +#endif + +/* + * TEMP_FAILURE_RETRY is defined by some, but not all, versions of + * . (Alas, it is not as standard as we'd hoped!) So, if it's + * not already defined, then define it here. + */ +#ifndef TEMP_FAILURE_RETRY +/* Used to retry syscalls that can return EINTR. */ +#define TEMP_FAILURE_RETRY(exp) ({ \ + typeof (exp) _rc; \ + do { \ + _rc = (exp); \ + } while (_rc == -1 && errno == EINTR); \ + _rc; }) +#endif + +#endif /* __LIB_UTILS_COMPAT_H */ diff --git a/third_party/android_system_core/include/utils/Condition.h b/third_party/android_system_core/include/utils/Condition.h new file mode 100644 index 00000000000000..5a7251982a65e4 --- /dev/null +++ b/third_party/android_system_core/include/utils/Condition.h @@ -0,0 +1,158 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_CONDITION_H +#define _LIBS_UTILS_CONDITION_H + +#include +#include +#include + +#if !defined(_WIN32) +# include +#endif + +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { +// --------------------------------------------------------------------------- + +/* + * Condition variable class. The implementation is system-dependent. + * + * Condition variables are paired up with mutexes. Lock the mutex, + * call wait(), then either re-wait() if things aren't quite what you want, + * or unlock the mutex and continue. All threads calling wait() must + * use the same mutex for a given Condition. + */ +class Condition { +public: + enum { + PRIVATE = 0, + SHARED = 1 + }; + + enum WakeUpType { + WAKE_UP_ONE = 0, + WAKE_UP_ALL = 1 + }; + + Condition(); + Condition(int type); + ~Condition(); + // Wait on the condition variable. Lock the mutex before calling. + status_t wait(Mutex& mutex); + // same with relative timeout + status_t waitRelative(Mutex& mutex, nsecs_t reltime); + // Signal the condition variable, allowing exactly one thread to continue. + void signal(); + // Signal the condition variable, allowing one or all threads to continue. + void signal(WakeUpType type) { + if (type == WAKE_UP_ONE) { + signal(); + } else { + broadcast(); + } + } + // Signal the condition variable, allowing all threads to continue. + void broadcast(); + +private: +#if !defined(_WIN32) + pthread_cond_t mCond; +#else + void* mState; +#endif +}; + +// --------------------------------------------------------------------------- + +#if !defined(_WIN32) + +inline Condition::Condition() { + pthread_cond_init(&mCond, NULL); +} +inline Condition::Condition(int type) { + if (type == SHARED) { + pthread_condattr_t attr; + pthread_condattr_init(&attr); + pthread_condattr_setpshared(&attr, PTHREAD_PROCESS_SHARED); + pthread_cond_init(&mCond, &attr); + pthread_condattr_destroy(&attr); + } else { + pthread_cond_init(&mCond, NULL); + } +} +inline Condition::~Condition() { + pthread_cond_destroy(&mCond); +} +inline status_t Condition::wait(Mutex& mutex) { + return -pthread_cond_wait(&mCond, &mutex.mMutex); +} +inline status_t Condition::waitRelative(Mutex& mutex, nsecs_t reltime) { +#if defined(HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE) + struct timespec ts; + ts.tv_sec = reltime/1000000000; + ts.tv_nsec = reltime%1000000000; + return -pthread_cond_timedwait_relative_np(&mCond, &mutex.mMutex, &ts); +#else // HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE + struct timespec ts; +#if defined(__linux__) + clock_gettime(CLOCK_REALTIME, &ts); +#else // __APPLE__ + // we don't support the clocks here. + struct timeval t; + gettimeofday(&t, NULL); + ts.tv_sec = t.tv_sec; + ts.tv_nsec= t.tv_usec*1000; +#endif + ts.tv_sec += reltime/1000000000; + ts.tv_nsec+= reltime%1000000000; + if (ts.tv_nsec >= 1000000000) { + ts.tv_nsec -= 1000000000; + ts.tv_sec += 1; + } + return -pthread_cond_timedwait(&mCond, &mutex.mMutex, &ts); +#endif // HAVE_PTHREAD_COND_TIMEDWAIT_RELATIVE +} +inline void Condition::signal() { + /* + * POSIX says pthread_cond_signal wakes up "one or more" waiting threads. + * However bionic follows the glibc guarantee which wakes up "exactly one" + * waiting thread. + * + * man 3 pthread_cond_signal + * pthread_cond_signal restarts one of the threads that are waiting on + * the condition variable cond. If no threads are waiting on cond, + * nothing happens. If several threads are waiting on cond, exactly one + * is restarted, but it is not specified which. + */ + pthread_cond_signal(&mCond); +} +inline void Condition::broadcast() { + pthread_cond_broadcast(&mCond); +} + +#endif // !defined(_WIN32) + +// --------------------------------------------------------------------------- +}; // namespace android +// --------------------------------------------------------------------------- + +#endif // _LIBS_UTILS_CONDITON_H diff --git a/third_party/android_system_core/include/utils/Debug.h b/third_party/android_system_core/include/utils/Debug.h new file mode 100644 index 00000000000000..08893bdaaf324f --- /dev/null +++ b/third_party/android_system_core/include/utils/Debug.h @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_DEBUG_H +#define ANDROID_UTILS_DEBUG_H + +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +#ifdef __cplusplus +template struct CompileTimeAssert; +template<> struct CompileTimeAssert {}; +#define COMPILE_TIME_ASSERT(_exp) \ + template class CompileTimeAssert< (_exp) >; +#endif +#define COMPILE_TIME_ASSERT_FUNCTION_SCOPE(_exp) \ + CompileTimeAssert<( _exp )>(); + +// --------------------------------------------------------------------------- + +#ifdef __cplusplus +template struct CompileTimeIfElse; +template +struct CompileTimeIfElse { typedef LHS TYPE; }; +template +struct CompileTimeIfElse { typedef RHS TYPE; }; +#endif + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_UTILS_DEBUG_H diff --git a/third_party/android_system_core/include/utils/Endian.h b/third_party/android_system_core/include/utils/Endian.h new file mode 100644 index 00000000000000..591cae0d3461d2 --- /dev/null +++ b/third_party/android_system_core/include/utils/Endian.h @@ -0,0 +1,35 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// Android endian-ness defines. +// +#ifndef _LIBS_UTILS_ENDIAN_H +#define _LIBS_UTILS_ENDIAN_H + +#if defined(__APPLE__) || defined(_WIN32) + +#define __BIG_ENDIAN 0x1000 +#define __LITTLE_ENDIAN 0x0001 +#define __BYTE_ORDER __LITTLE_ENDIAN + +#else + +#include + +#endif + +#endif /*_LIBS_UTILS_ENDIAN_H*/ diff --git a/third_party/android_system_core/include/utils/Errors.h b/third_party/android_system_core/include/utils/Errors.h new file mode 100644 index 00000000000000..46173db4a3de82 --- /dev/null +++ b/third_party/android_system_core/include/utils/Errors.h @@ -0,0 +1,88 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_ERRORS_H +#define ANDROID_ERRORS_H + +#include +#include + +namespace android { + +// use this type to return error codes +#ifdef HAVE_MS_C_RUNTIME +typedef int status_t; +#else +typedef int32_t status_t; +#endif + +/* the MS C runtime lacks a few error codes */ + +/* + * Error codes. + * All error codes are negative values. + */ + +// Win32 #defines NO_ERROR as well. It has the same value, so there's no +// real conflict, though it's a bit awkward. +#ifdef _WIN32 +# undef NO_ERROR +#endif + +enum { + OK = 0, // Everything's swell. + NO_ERROR = 0, // No errors. + + UNKNOWN_ERROR = (-2147483647-1), // INT32_MIN value + + NO_MEMORY = -ENOMEM, + INVALID_OPERATION = -ENOSYS, + BAD_VALUE = -EINVAL, + BAD_TYPE = (UNKNOWN_ERROR + 1), + NAME_NOT_FOUND = -ENOENT, + PERMISSION_DENIED = -EPERM, + NO_INIT = -ENODEV, + ALREADY_EXISTS = -EEXIST, + DEAD_OBJECT = -EPIPE, + FAILED_TRANSACTION = (UNKNOWN_ERROR + 2), + JPARKS_BROKE_IT = -EPIPE, +#if !defined(HAVE_MS_C_RUNTIME) + BAD_INDEX = -EOVERFLOW, + NOT_ENOUGH_DATA = -ENODATA, + WOULD_BLOCK = -EWOULDBLOCK, + TIMED_OUT = -ETIMEDOUT, + UNKNOWN_TRANSACTION = -EBADMSG, +#else + BAD_INDEX = -E2BIG, + NOT_ENOUGH_DATA = (UNKNOWN_ERROR + 3), + WOULD_BLOCK = (UNKNOWN_ERROR + 4), + TIMED_OUT = (UNKNOWN_ERROR + 5), + UNKNOWN_TRANSACTION = (UNKNOWN_ERROR + 6), +#endif + FDS_NOT_ALLOWED = (UNKNOWN_ERROR + 7), +}; + +// Restore define; enumeration is in "android" namespace, so the value defined +// there won't work for Win32 code in a different namespace. +#ifdef _WIN32 +# define NO_ERROR 0L +#endif + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_ERRORS_H diff --git a/third_party/android_system_core/include/utils/FileMap.h b/third_party/android_system_core/include/utils/FileMap.h new file mode 100644 index 00000000000000..f70fc927e4ca36 --- /dev/null +++ b/third_party/android_system_core/include/utils/FileMap.h @@ -0,0 +1,126 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// Encapsulate a shared file mapping. +// +#ifndef __LIBS_FILE_MAP_H +#define __LIBS_FILE_MAP_H + +#include + +#include + +#if defined(__MINGW32__) +// Ensure that we always pull in winsock2.h before windows.h +#ifdef HAVE_WINSOCK +#include +#endif +#include +#endif + +namespace android { + +/* + * This represents a memory-mapped file. It might be the entire file or + * only part of it. This requires a little bookkeeping because the mapping + * needs to be aligned on page boundaries, and in some cases we'd like to + * have multiple references to the mapped area without creating additional + * maps. + * + * This always uses MAP_SHARED. + * + * TODO: we should be able to create a new FileMap that is a subset of + * an existing FileMap and shares the underlying mapped pages. Requires + * completing the refcounting stuff and possibly introducing the notion + * of a FileMap hierarchy. + */ +class FileMap { +public: + FileMap(void); + + /* + * Create a new mapping on an open file. + * + * Closing the file descriptor does not unmap the pages, so we don't + * claim ownership of the fd. + * + * Returns "false" on failure. + */ + bool create(const char* origFileName, int fd, + off64_t offset, size_t length, bool readOnly); + + ~FileMap(void); + + /* + * Return the name of the file this map came from, if known. + */ + const char* getFileName(void) const { return mFileName; } + + /* + * Get a pointer to the piece of the file we requested. + */ + void* getDataPtr(void) const { return mDataPtr; } + + /* + * Get the length we requested. + */ + size_t getDataLength(void) const { return mDataLength; } + + /* + * Get the data offset used to create this map. + */ + off64_t getDataOffset(void) const { return mDataOffset; } + + /* + * This maps directly to madvise() values, but allows us to avoid + * including everywhere. + */ + enum MapAdvice { + NORMAL, RANDOM, SEQUENTIAL, WILLNEED, DONTNEED + }; + + /* + * Apply an madvise() call to the entire file. + * + * Returns 0 on success, -1 on failure. + */ + int advise(MapAdvice advice); + +protected: + +private: + // these are not implemented + FileMap(const FileMap& src); + const FileMap& operator=(const FileMap& src); + + char* mFileName; // original file name, if known + void* mBasePtr; // base of mmap area; page aligned + size_t mBaseLength; // length, measured from "mBasePtr" + off64_t mDataOffset; // offset used when map was created + void* mDataPtr; // start of requested data, offset from base + size_t mDataLength; // length, measured from "mDataPtr" +#if defined(__MINGW32__) + HANDLE mFileHandle; // Win32 file handle + HANDLE mFileMapping; // Win32 file mapping handle +#endif + + static long mPageSize; +}; + +}; // namespace android + +#endif // __LIBS_FILE_MAP_H diff --git a/third_party/android_system_core/include/utils/Flattenable.h b/third_party/android_system_core/include/utils/Flattenable.h new file mode 100644 index 00000000000000..882a8b2499a1c9 --- /dev/null +++ b/third_party/android_system_core/include/utils/Flattenable.h @@ -0,0 +1,198 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_FLATTENABLE_H +#define ANDROID_UTILS_FLATTENABLE_H + + +#include +#include +#include +#include + +namespace android { + + +class FlattenableUtils { +public: + template + static size_t align(size_t size) { + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( !(N & (N-1)) ); + return (size + (N-1)) & ~(N-1); + } + + template + static size_t align(void const*& buffer) { + COMPILE_TIME_ASSERT_FUNCTION_SCOPE( !(N & (N-1)) ); + intptr_t b = intptr_t(buffer); + buffer = (void*)((intptr_t(buffer) + (N-1)) & ~(N-1)); + return size_t(intptr_t(buffer) - b); + } + + template + static size_t align(void*& buffer) { + return align( const_cast(buffer) ); + } + + static void advance(void*& buffer, size_t& size, size_t offset) { + buffer = reinterpret_cast( intptr_t(buffer) + offset ); + size -= offset; + } + + static void advance(void const*& buffer, size_t& size, size_t offset) { + buffer = reinterpret_cast( intptr_t(buffer) + offset ); + size -= offset; + } + + // write a POD structure + template + static void write(void*& buffer, size_t& size, const T& value) { + *static_cast(buffer) = value; + advance(buffer, size, sizeof(T)); + } + + // read a POD structure + template + static void read(void const*& buffer, size_t& size, T& value) { + value = *static_cast(buffer); + advance(buffer, size, sizeof(T)); + } +}; + + +/* + * The Flattenable protocol allows an object to serialize itself out + * to a byte-buffer and an array of file descriptors. + * Flattenable objects must implement this protocol. + */ + +template +class Flattenable { +public: + // size in bytes of the flattened object + inline size_t getFlattenedSize() const; + + // number of file descriptors to flatten + inline size_t getFdCount() const; + + // flattens the object into buffer. + // size should be at least of getFlattenedSize() + // file descriptors are written in the fds[] array but ownership is + // not transfered (ie: they must be dupped by the caller of + // flatten() if needed). + inline status_t flatten(void*& buffer, size_t& size, int*& fds, size_t& count) const; + + // unflattens the object from buffer. + // size should be equal to the value of getFlattenedSize() when the + // object was flattened. + // unflattened file descriptors are found in the fds[] array and + // don't need to be dupped(). ie: the caller of unflatten doesn't + // keep ownership. If a fd is not retained by unflatten() it must be + // explicitly closed. + inline status_t unflatten(void const*& buffer, size_t& size, int const*& fds, size_t& count); +}; + +template +inline size_t Flattenable::getFlattenedSize() const { + return static_cast(this)->T::getFlattenedSize(); +} +template +inline size_t Flattenable::getFdCount() const { + return static_cast(this)->T::getFdCount(); +} +template +inline status_t Flattenable::flatten( + void*& buffer, size_t& size, int*& fds, size_t& count) const { + return static_cast(this)->T::flatten(buffer, size, fds, count); +} +template +inline status_t Flattenable::unflatten( + void const*& buffer, size_t& size, int const*& fds, size_t& count) { + return static_cast(this)->T::unflatten(buffer, size, fds, count); +} + +/* + * LightFlattenable is a protocol allowing object to serialize themselves out + * to a byte-buffer. Because it doesn't handle file-descriptors, + * LightFlattenable is usually more size efficient than Flattenable. + * LightFlattenable objects must implement this protocol. + */ +template +class LightFlattenable { +public: + // returns whether this object always flatten into the same size. + // for efficiency, this should always be inline. + inline bool isFixedSize() const; + + // returns size in bytes of the flattened object. must be a constant. + inline size_t getFlattenedSize() const; + + // flattens the object into buffer. + inline status_t flatten(void* buffer, size_t size) const; + + // unflattens the object from buffer of given size. + inline status_t unflatten(void const* buffer, size_t size); +}; + +template +inline bool LightFlattenable::isFixedSize() const { + return static_cast(this)->T::isFixedSize(); +} +template +inline size_t LightFlattenable::getFlattenedSize() const { + return static_cast(this)->T::getFlattenedSize(); +} +template +inline status_t LightFlattenable::flatten(void* buffer, size_t size) const { + return static_cast(this)->T::flatten(buffer, size); +} +template +inline status_t LightFlattenable::unflatten(void const* buffer, size_t size) { + return static_cast(this)->T::unflatten(buffer, size); +} + +/* + * LightFlattenablePod is an implementation of the LightFlattenable protocol + * for POD (plain-old-data) objects. + * Simply derive from LightFlattenablePod to make Foo flattenable; no + * need to implement any methods; obviously Foo must be a POD structure. + */ +template +class LightFlattenablePod : public LightFlattenable { +public: + inline bool isFixedSize() const { + return true; + } + + inline size_t getFlattenedSize() const { + return sizeof(T); + } + inline status_t flatten(void* buffer, size_t size) const { + if (size < sizeof(T)) return NO_MEMORY; + *reinterpret_cast(buffer) = *static_cast(this); + return NO_ERROR; + } + inline status_t unflatten(void const* buffer, size_t) { + *static_cast(this) = *reinterpret_cast(buffer); + return NO_ERROR; + } +}; + + +}; // namespace android + + +#endif /* ANDROID_UTILS_FLATTENABLE_H */ diff --git a/third_party/android_system_core/include/utils/Functor.h b/third_party/android_system_core/include/utils/Functor.h new file mode 100644 index 00000000000000..09ea614b614f29 --- /dev/null +++ b/third_party/android_system_core/include/utils/Functor.h @@ -0,0 +1,33 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_FUNCTOR_H +#define ANDROID_FUNCTOR_H + +#include + +namespace android { + +class Functor { +public: + Functor() {} + virtual ~Functor() {} + virtual status_t operator ()(int /*what*/, void* /*data*/) { return NO_ERROR; } +}; + +}; // namespace android + +#endif // ANDROID_FUNCTOR_H diff --git a/third_party/android_system_core/include/utils/JenkinsHash.h b/third_party/android_system_core/include/utils/JenkinsHash.h new file mode 100644 index 00000000000000..7da5dbd6a91321 --- /dev/null +++ b/third_party/android_system_core/include/utils/JenkinsHash.h @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* Implementation of Jenkins one-at-a-time hash function. These choices are + * optimized for code size and portability, rather than raw speed. But speed + * should still be quite good. + **/ + +#ifndef ANDROID_JENKINS_HASH_H +#define ANDROID_JENKINS_HASH_H + +#include + +namespace android { + +/* The Jenkins hash of a sequence of 32 bit words A, B, C is: + * Whiten(Mix(Mix(Mix(0, A), B), C)) */ + +inline uint32_t JenkinsHashMix(uint32_t hash, uint32_t data) { + hash += data; + hash += (hash << 10); + hash ^= (hash >> 6); + return hash; +} + +hash_t JenkinsHashWhiten(uint32_t hash); + +/* Helpful utility functions for hashing data in 32 bit chunks */ +uint32_t JenkinsHashMixBytes(uint32_t hash, const uint8_t* bytes, size_t size); + +uint32_t JenkinsHashMixShorts(uint32_t hash, const uint16_t* shorts, size_t size); + +} + +#endif // ANDROID_JENKINS_HASH_H diff --git a/third_party/android_system_core/include/utils/KeyedVector.h b/third_party/android_system_core/include/utils/KeyedVector.h new file mode 100644 index 00000000000000..c4faae0b76ae79 --- /dev/null +++ b/third_party/android_system_core/include/utils/KeyedVector.h @@ -0,0 +1,224 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_KEYED_VECTOR_H +#define ANDROID_KEYED_VECTOR_H + +#include +#include +#include + +#include + +#include +#include +#include + +// --------------------------------------------------------------------------- + +namespace android { + +template +class KeyedVector +{ +public: + typedef KEY key_type; + typedef VALUE value_type; + + inline KeyedVector(); + + /* + * empty the vector + */ + + inline void clear() { mVector.clear(); } + + /*! + * vector stats + */ + + //! returns number of items in the vector + inline size_t size() const { return mVector.size(); } + //! returns whether or not the vector is empty + inline bool isEmpty() const { return mVector.isEmpty(); } + //! returns how many items can be stored without reallocating the backing store + inline size_t capacity() const { return mVector.capacity(); } + //! sets the capacity. capacity can never be reduced less than size() + inline ssize_t setCapacity(size_t size) { return mVector.setCapacity(size); } + + // returns true if the arguments is known to be identical to this vector + inline bool isIdenticalTo(const KeyedVector& rhs) const; + + /*! + * accessors + */ + const VALUE& valueFor(const KEY& key) const; + const VALUE& valueAt(size_t index) const; + const KEY& keyAt(size_t index) const; + ssize_t indexOfKey(const KEY& key) const; + const VALUE& operator[] (size_t index) const; + + /*! + * modifying the array + */ + + VALUE& editValueFor(const KEY& key); + VALUE& editValueAt(size_t index); + + /*! + * add/insert/replace items + */ + + ssize_t add(const KEY& key, const VALUE& item); + ssize_t replaceValueFor(const KEY& key, const VALUE& item); + ssize_t replaceValueAt(size_t index, const VALUE& item); + + /*! + * remove items + */ + + ssize_t removeItem(const KEY& key); + ssize_t removeItemsAt(size_t index, size_t count = 1); + +private: + SortedVector< key_value_pair_t > mVector; +}; + +// KeyedVector can be trivially moved using memcpy() because its +// underlying SortedVector can be trivially moved. +template struct trait_trivial_move > { + enum { value = trait_trivial_move > >::value }; +}; + + +// --------------------------------------------------------------------------- + +/** + * Variation of KeyedVector that holds a default value to return when + * valueFor() is called with a key that doesn't exist. + */ +template +class DefaultKeyedVector : public KeyedVector +{ +public: + inline DefaultKeyedVector(const VALUE& defValue = VALUE()); + const VALUE& valueFor(const KEY& key) const; + +private: + VALUE mDefault; +}; + +// --------------------------------------------------------------------------- + +template inline +KeyedVector::KeyedVector() +{ +} + +template inline +bool KeyedVector::isIdenticalTo(const KeyedVector& rhs) const { + return mVector.array() == rhs.mVector.array(); +} + +template inline +ssize_t KeyedVector::indexOfKey(const KEY& key) const { + return mVector.indexOf( key_value_pair_t(key) ); +} + +template inline +const VALUE& KeyedVector::valueFor(const KEY& key) const { + ssize_t i = this->indexOfKey(key); + LOG_ALWAYS_FATAL_IF(i<0, "%s: key not found", __PRETTY_FUNCTION__); + return mVector.itemAt(i).value; +} + +template inline +const VALUE& KeyedVector::valueAt(size_t index) const { + return mVector.itemAt(index).value; +} + +template inline +const VALUE& KeyedVector::operator[] (size_t index) const { + return valueAt(index); +} + +template inline +const KEY& KeyedVector::keyAt(size_t index) const { + return mVector.itemAt(index).key; +} + +template inline +VALUE& KeyedVector::editValueFor(const KEY& key) { + ssize_t i = this->indexOfKey(key); + LOG_ALWAYS_FATAL_IF(i<0, "%s: key not found", __PRETTY_FUNCTION__); + return mVector.editItemAt(i).value; +} + +template inline +VALUE& KeyedVector::editValueAt(size_t index) { + return mVector.editItemAt(index).value; +} + +template inline +ssize_t KeyedVector::add(const KEY& key, const VALUE& value) { + return mVector.add( key_value_pair_t(key, value) ); +} + +template inline +ssize_t KeyedVector::replaceValueFor(const KEY& key, const VALUE& value) { + key_value_pair_t pair(key, value); + mVector.remove(pair); + return mVector.add(pair); +} + +template inline +ssize_t KeyedVector::replaceValueAt(size_t index, const VALUE& item) { + if (index inline +ssize_t KeyedVector::removeItem(const KEY& key) { + return mVector.remove(key_value_pair_t(key)); +} + +template inline +ssize_t KeyedVector::removeItemsAt(size_t index, size_t count) { + return mVector.removeItemsAt(index, count); +} + +// --------------------------------------------------------------------------- + +template inline +DefaultKeyedVector::DefaultKeyedVector(const VALUE& defValue) + : mDefault(defValue) +{ +} + +template inline +const VALUE& DefaultKeyedVector::valueFor(const KEY& key) const { + ssize_t i = this->indexOfKey(key); + return i >= 0 ? KeyedVector::valueAt(i) : mDefault; +} + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_KEYED_VECTOR_H diff --git a/third_party/android_system_core/include/utils/LinearTransform.h b/third_party/android_system_core/include/utils/LinearTransform.h new file mode 100644 index 00000000000000..04cb355c7ff77c --- /dev/null +++ b/third_party/android_system_core/include/utils/LinearTransform.h @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2011 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_LINEAR_TRANSFORM_H +#define _LIBS_UTILS_LINEAR_TRANSFORM_H + +#include + +namespace android { + +// LinearTransform defines a structure which hold the definition of a +// transformation from single dimensional coordinate system A into coordinate +// system B (and back again). Values in A and in B are 64 bit, the linear +// scale factor is expressed as a rational number using two 32 bit values. +// +// Specifically, let +// f(a) = b +// F(b) = f^-1(b) = a +// then +// +// f(a) = (((a - a_zero) * a_to_b_numer) / a_to_b_denom) + b_zero; +// +// and +// +// F(b) = (((b - b_zero) * a_to_b_denom) / a_to_b_numer) + a_zero; +// +struct LinearTransform { + int64_t a_zero; + int64_t b_zero; + int32_t a_to_b_numer; + uint32_t a_to_b_denom; + + // Transform from A->B + // Returns true on success, or false in the case of a singularity or an + // overflow. + bool doForwardTransform(int64_t a_in, int64_t* b_out) const; + + // Transform from B->A + // Returns true on success, or false in the case of a singularity or an + // overflow. + bool doReverseTransform(int64_t b_in, int64_t* a_out) const; + + // Helpers which will reduce the fraction N/D using Euclid's method. + template static void reduce(T* N, T* D); + static void reduce(int32_t* N, uint32_t* D); +}; + + +} + +#endif // _LIBS_UTILS_LINEAR_TRANSFORM_H diff --git a/third_party/android_system_core/include/utils/List.h b/third_party/android_system_core/include/utils/List.h new file mode 100644 index 00000000000000..403cd7f1e54021 --- /dev/null +++ b/third_party/android_system_core/include/utils/List.h @@ -0,0 +1,332 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// Templated list class. Normally we'd use STL, but we don't have that. +// This class mimics STL's interfaces. +// +// Objects are copied into the list with the '=' operator or with copy- +// construction, so if the compiler's auto-generated versions won't work for +// you, define your own. +// +// The only class you want to use from here is "List". +// +#ifndef _LIBS_UTILS_LIST_H +#define _LIBS_UTILS_LIST_H + +#include +#include + +namespace android { + +/* + * Doubly-linked list. Instantiate with "List myList". + * + * Objects added to the list are copied using the assignment operator, + * so this must be defined. + */ +template +class List +{ +protected: + /* + * One element in the list. + */ + class _Node { + public: + explicit _Node(const T& val) : mVal(val) {} + ~_Node() {} + inline T& getRef() { return mVal; } + inline const T& getRef() const { return mVal; } + inline _Node* getPrev() const { return mpPrev; } + inline _Node* getNext() const { return mpNext; } + inline void setVal(const T& val) { mVal = val; } + inline void setPrev(_Node* ptr) { mpPrev = ptr; } + inline void setNext(_Node* ptr) { mpNext = ptr; } + private: + friend class List; + friend class _ListIterator; + T mVal; + _Node* mpPrev; + _Node* mpNext; + }; + + /* + * Iterator for walking through the list. + */ + + template + struct CONST_ITERATOR { + typedef _Node const * NodePtr; + typedef const TYPE Type; + }; + + template + struct NON_CONST_ITERATOR { + typedef _Node* NodePtr; + typedef TYPE Type; + }; + + template< + typename U, + template class Constness + > + class _ListIterator { + typedef _ListIterator _Iter; + typedef typename Constness::NodePtr _NodePtr; + typedef typename Constness::Type _Type; + + explicit _ListIterator(_NodePtr ptr) : mpNode(ptr) {} + + public: + _ListIterator() {} + _ListIterator(const _Iter& rhs) : mpNode(rhs.mpNode) {} + ~_ListIterator() {} + + // this will handle conversions from iterator to const_iterator + // (and also all convertible iterators) + // Here, in this implementation, the iterators can be converted + // if the nodes can be converted + template explicit + _ListIterator(const V& rhs) : mpNode(rhs.mpNode) {} + + + /* + * Dereference operator. Used to get at the juicy insides. + */ + _Type& operator*() const { return mpNode->getRef(); } + _Type* operator->() const { return &(mpNode->getRef()); } + + /* + * Iterator comparison. + */ + inline bool operator==(const _Iter& right) const { + return mpNode == right.mpNode; } + + inline bool operator!=(const _Iter& right) const { + return mpNode != right.mpNode; } + + /* + * handle comparisons between iterator and const_iterator + */ + template + inline bool operator==(const OTHER& right) const { + return mpNode == right.mpNode; } + + template + inline bool operator!=(const OTHER& right) const { + return mpNode != right.mpNode; } + + /* + * Incr/decr, used to move through the list. + */ + inline _Iter& operator++() { // pre-increment + mpNode = mpNode->getNext(); + return *this; + } + const _Iter operator++(int) { // post-increment + _Iter tmp(*this); + mpNode = mpNode->getNext(); + return tmp; + } + inline _Iter& operator--() { // pre-increment + mpNode = mpNode->getPrev(); + return *this; + } + const _Iter operator--(int) { // post-increment + _Iter tmp(*this); + mpNode = mpNode->getPrev(); + return tmp; + } + + inline _NodePtr getNode() const { return mpNode; } + + _NodePtr mpNode; /* should be private, but older gcc fails */ + private: + friend class List; + }; + +public: + List() { + prep(); + } + List(const List& src) { // copy-constructor + prep(); + insert(begin(), src.begin(), src.end()); + } + virtual ~List() { + clear(); + delete[] (unsigned char*) mpMiddle; + } + + typedef _ListIterator iterator; + typedef _ListIterator const_iterator; + + List& operator=(const List& right); + + /* returns true if the list is empty */ + inline bool empty() const { return mpMiddle->getNext() == mpMiddle; } + + /* return #of elements in list */ + size_t size() const { + return size_t(distance(begin(), end())); + } + + /* + * Return the first element or one past the last element. The + * _Node* we're returning is converted to an "iterator" by a + * constructor in _ListIterator. + */ + inline iterator begin() { + return iterator(mpMiddle->getNext()); + } + inline const_iterator begin() const { + return const_iterator(const_cast<_Node const*>(mpMiddle->getNext())); + } + inline iterator end() { + return iterator(mpMiddle); + } + inline const_iterator end() const { + return const_iterator(const_cast<_Node const*>(mpMiddle)); + } + + /* add the object to the head or tail of the list */ + void push_front(const T& val) { insert(begin(), val); } + void push_back(const T& val) { insert(end(), val); } + + /* insert before the current node; returns iterator at new node */ + iterator insert(iterator posn, const T& val) + { + _Node* newNode = new _Node(val); // alloc & copy-construct + newNode->setNext(posn.getNode()); + newNode->setPrev(posn.getNode()->getPrev()); + posn.getNode()->getPrev()->setNext(newNode); + posn.getNode()->setPrev(newNode); + return iterator(newNode); + } + + /* insert a range of elements before the current node */ + void insert(iterator posn, const_iterator first, const_iterator last) { + for ( ; first != last; ++first) + insert(posn, *first); + } + + /* remove one entry; returns iterator at next node */ + iterator erase(iterator posn) { + _Node* pNext = posn.getNode()->getNext(); + _Node* pPrev = posn.getNode()->getPrev(); + pPrev->setNext(pNext); + pNext->setPrev(pPrev); + delete posn.getNode(); + return iterator(pNext); + } + + /* remove a range of elements */ + iterator erase(iterator first, iterator last) { + while (first != last) + erase(first++); // don't erase than incr later! + return iterator(last); + } + + /* remove all contents of the list */ + void clear() { + _Node* pCurrent = mpMiddle->getNext(); + _Node* pNext; + + while (pCurrent != mpMiddle) { + pNext = pCurrent->getNext(); + delete pCurrent; + pCurrent = pNext; + } + mpMiddle->setPrev(mpMiddle); + mpMiddle->setNext(mpMiddle); + } + + /* + * Measure the distance between two iterators. On exist, "first" + * will be equal to "last". The iterators must refer to the same + * list. + * + * FIXME: This is actually a generic iterator function. It should be a + * template function at the top-level with specializations for things like + * vector<>, which can just do pointer math). Here we limit it to + * _ListIterator of the same type but different constness. + */ + template< + typename U, + template class CL, + template class CR + > + ptrdiff_t distance( + _ListIterator first, _ListIterator last) const + { + ptrdiff_t count = 0; + while (first != last) { + ++first; + ++count; + } + return count; + } + +private: + /* + * I want a _Node but don't need it to hold valid data. More + * to the point, I don't want T's constructor to fire, since it + * might have side-effects or require arguments. So, we do this + * slightly uncouth storage alloc. + */ + void prep() { + mpMiddle = (_Node*) new unsigned char[sizeof(_Node)]; + mpMiddle->setPrev(mpMiddle); + mpMiddle->setNext(mpMiddle); + } + + /* + * This node plays the role of "pointer to head" and "pointer to tail". + * It sits in the middle of a circular list of nodes. The iterator + * runs around the circle until it encounters this one. + */ + _Node* mpMiddle; +}; + +/* + * Assignment operator. + * + * The simplest way to do this would be to clear out the target list and + * fill it with the source. However, we can speed things along by + * re-using existing elements. + */ +template +List& List::operator=(const List& right) +{ + if (this == &right) + return *this; // self-assignment + iterator firstDst = begin(); + iterator lastDst = end(); + const_iterator firstSrc = right.begin(); + const_iterator lastSrc = right.end(); + while (firstSrc != lastSrc && firstDst != lastDst) + *firstDst++ = *firstSrc++; + if (firstSrc == lastSrc) // ran out of elements in source? + erase(firstDst, lastDst); // yes, erase any extras + else + insert(lastDst, firstSrc, lastSrc); // copy remaining over + return *this; +} + +}; // namespace android + +#endif // _LIBS_UTILS_LIST_H diff --git a/third_party/android_system_core/include/utils/Log.h b/third_party/android_system_core/include/utils/Log.h new file mode 100644 index 00000000000000..4259c86d1ac486 --- /dev/null +++ b/third_party/android_system_core/include/utils/Log.h @@ -0,0 +1,71 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// C/C++ logging functions. See the logging documentation for API details. +// +// We'd like these to be available from C code (in case we import some from +// somewhere), so this has a C interface. +// +// The output will be correct when the log file is shared between multiple +// threads and/or multiple processes so long as the operating system +// supports O_APPEND. These calls have mutex-protected data structures +// and so are NOT reentrant. Do not use LOG in a signal handler. +// +#ifndef _LIBS_UTILS_LOG_H +#define _LIBS_UTILS_LOG_H + +#include +#include + +#ifdef __cplusplus + +namespace android { + +/* + * A very simple utility that yells in the log when an operation takes too long. + */ +class LogIfSlow { +public: + LogIfSlow(const char* tag, android_LogPriority priority, + int timeoutMillis, const char* message); + ~LogIfSlow(); + +private: + const char* const mTag; + const android_LogPriority mPriority; + const int mTimeoutMillis; + const char* const mMessage; + const int64_t mStart; +}; + +/* + * Writes the specified debug log message if this block takes longer than the + * specified number of milliseconds to run. Includes the time actually taken. + * + * { + * ALOGD_IF_SLOW(50, "Excessive delay doing something."); + * doSomething(); + * } + */ +#define ALOGD_IF_SLOW(timeoutMillis, message) \ + android::LogIfSlow _logIfSlow(LOG_TAG, ANDROID_LOG_DEBUG, timeoutMillis, message); + +} // namespace android + +#endif // __cplusplus + +#endif // _LIBS_UTILS_LOG_H diff --git a/third_party/android_system_core/include/utils/Looper.h b/third_party/android_system_core/include/utils/Looper.h new file mode 100644 index 00000000000000..da2d5f2b5bdba7 --- /dev/null +++ b/third_party/android_system_core/include/utils/Looper.h @@ -0,0 +1,487 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef UTILS_LOOPER_H +#define UTILS_LOOPER_H + +#include +#include +#include +#include + +#include + +namespace android { + +/* + * NOTE: Since Looper is used to implement the NDK ALooper, the Looper + * enums and the signature of Looper_callbackFunc need to align with + * that implementation. + */ + +/** + * For callback-based event loops, this is the prototype of the function + * that is called when a file descriptor event occurs. + * It is given the file descriptor it is associated with, + * a bitmask of the poll events that were triggered (typically EVENT_INPUT), + * and the data pointer that was originally supplied. + * + * Implementations should return 1 to continue receiving callbacks, or 0 + * to have this file descriptor and callback unregistered from the looper. + */ +typedef int (*Looper_callbackFunc)(int fd, int events, void* data); + +/** + * A message that can be posted to a Looper. + */ +struct Message { + Message() : what(0) { } + Message(int what) : what(what) { } + + /* The message type. (interpretation is left up to the handler) */ + int what; +}; + + +/** + * Interface for a Looper message handler. + * + * The Looper holds a strong reference to the message handler whenever it has + * a message to deliver to it. Make sure to call Looper::removeMessages + * to remove any pending messages destined for the handler so that the handler + * can be destroyed. + */ +class MessageHandler : public virtual RefBase { +protected: + virtual ~MessageHandler() { } + +public: + /** + * Handles a message. + */ + virtual void handleMessage(const Message& message) = 0; +}; + + +/** + * A simple proxy that holds a weak reference to a message handler. + */ +class WeakMessageHandler : public MessageHandler { +protected: + virtual ~WeakMessageHandler(); + +public: + WeakMessageHandler(const wp& handler); + virtual void handleMessage(const Message& message); + +private: + wp mHandler; +}; + + +/** + * A looper callback. + */ +class LooperCallback : public virtual RefBase { +protected: + virtual ~LooperCallback() { } + +public: + /** + * Handles a poll event for the given file descriptor. + * It is given the file descriptor it is associated with, + * a bitmask of the poll events that were triggered (typically EVENT_INPUT), + * and the data pointer that was originally supplied. + * + * Implementations should return 1 to continue receiving callbacks, or 0 + * to have this file descriptor and callback unregistered from the looper. + */ + virtual int handleEvent(int fd, int events, void* data) = 0; +}; + +/** + * Wraps a Looper_callbackFunc function pointer. + */ +class SimpleLooperCallback : public LooperCallback { +protected: + virtual ~SimpleLooperCallback(); + +public: + SimpleLooperCallback(Looper_callbackFunc callback); + virtual int handleEvent(int fd, int events, void* data); + +private: + Looper_callbackFunc mCallback; +}; + +/** + * A polling loop that supports monitoring file descriptor events, optionally + * using callbacks. The implementation uses epoll() internally. + * + * A looper can be associated with a thread although there is no requirement that it must be. + */ +class Looper : public RefBase { +protected: + virtual ~Looper(); + +public: + enum { + /** + * Result from Looper_pollOnce() and Looper_pollAll(): + * The poll was awoken using wake() before the timeout expired + * and no callbacks were executed and no other file descriptors were ready. + */ + POLL_WAKE = -1, + + /** + * Result from Looper_pollOnce() and Looper_pollAll(): + * One or more callbacks were executed. + */ + POLL_CALLBACK = -2, + + /** + * Result from Looper_pollOnce() and Looper_pollAll(): + * The timeout expired. + */ + POLL_TIMEOUT = -3, + + /** + * Result from Looper_pollOnce() and Looper_pollAll(): + * An error occurred. + */ + POLL_ERROR = -4, + }; + + /** + * Flags for file descriptor events that a looper can monitor. + * + * These flag bits can be combined to monitor multiple events at once. + */ + enum { + /** + * The file descriptor is available for read operations. + */ + EVENT_INPUT = 1 << 0, + + /** + * The file descriptor is available for write operations. + */ + EVENT_OUTPUT = 1 << 1, + + /** + * The file descriptor has encountered an error condition. + * + * The looper always sends notifications about errors; it is not necessary + * to specify this event flag in the requested event set. + */ + EVENT_ERROR = 1 << 2, + + /** + * The file descriptor was hung up. + * For example, indicates that the remote end of a pipe or socket was closed. + * + * The looper always sends notifications about hangups; it is not necessary + * to specify this event flag in the requested event set. + */ + EVENT_HANGUP = 1 << 3, + + /** + * The file descriptor is invalid. + * For example, the file descriptor was closed prematurely. + * + * The looper always sends notifications about invalid file descriptors; it is not necessary + * to specify this event flag in the requested event set. + */ + EVENT_INVALID = 1 << 4, + }; + + enum { + /** + * Option for Looper_prepare: this looper will accept calls to + * Looper_addFd() that do not have a callback (that is provide NULL + * for the callback). In this case the caller of Looper_pollOnce() + * or Looper_pollAll() MUST check the return from these functions to + * discover when data is available on such fds and process it. + */ + PREPARE_ALLOW_NON_CALLBACKS = 1<<0 + }; + + /** + * Creates a looper. + * + * If allowNonCallbaks is true, the looper will allow file descriptors to be + * registered without associated callbacks. This assumes that the caller of + * pollOnce() is prepared to handle callback-less events itself. + */ + Looper(bool allowNonCallbacks); + + /** + * Returns whether this looper instance allows the registration of file descriptors + * using identifiers instead of callbacks. + */ + bool getAllowNonCallbacks() const; + + /** + * Waits for events to be available, with optional timeout in milliseconds. + * Invokes callbacks for all file descriptors on which an event occurred. + * + * If the timeout is zero, returns immediately without blocking. + * If the timeout is negative, waits indefinitely until an event appears. + * + * Returns POLL_WAKE if the poll was awoken using wake() before + * the timeout expired and no callbacks were invoked and no other file + * descriptors were ready. + * + * Returns POLL_CALLBACK if one or more callbacks were invoked. + * + * Returns POLL_TIMEOUT if there was no data before the given + * timeout expired. + * + * Returns POLL_ERROR if an error occurred. + * + * Returns a value >= 0 containing an identifier if its file descriptor has data + * and it has no callback function (requiring the caller here to handle it). + * In this (and only this) case outFd, outEvents and outData will contain the poll + * events and data associated with the fd, otherwise they will be set to NULL. + * + * This method does not return until it has finished invoking the appropriate callbacks + * for all file descriptors that were signalled. + */ + int pollOnce(int timeoutMillis, int* outFd, int* outEvents, void** outData); + inline int pollOnce(int timeoutMillis) { + return pollOnce(timeoutMillis, NULL, NULL, NULL); + } + + /** + * Like pollOnce(), but performs all pending callbacks until all + * data has been consumed or a file descriptor is available with no callback. + * This function will never return POLL_CALLBACK. + */ + int pollAll(int timeoutMillis, int* outFd, int* outEvents, void** outData); + inline int pollAll(int timeoutMillis) { + return pollAll(timeoutMillis, NULL, NULL, NULL); + } + + /** + * Wakes the poll asynchronously. + * + * This method can be called on any thread. + * This method returns immediately. + */ + void wake(); + + /** + * Adds a new file descriptor to be polled by the looper. + * If the same file descriptor was previously added, it is replaced. + * + * "fd" is the file descriptor to be added. + * "ident" is an identifier for this event, which is returned from pollOnce(). + * The identifier must be >= 0, or POLL_CALLBACK if providing a non-NULL callback. + * "events" are the poll events to wake up on. Typically this is EVENT_INPUT. + * "callback" is the function to call when there is an event on the file descriptor. + * "data" is a private data pointer to supply to the callback. + * + * There are two main uses of this function: + * + * (1) If "callback" is non-NULL, then this function will be called when there is + * data on the file descriptor. It should execute any events it has pending, + * appropriately reading from the file descriptor. The 'ident' is ignored in this case. + * + * (2) If "callback" is NULL, the 'ident' will be returned by Looper_pollOnce + * when its file descriptor has data available, requiring the caller to take + * care of processing it. + * + * Returns 1 if the file descriptor was added, 0 if the arguments were invalid. + * + * This method can be called on any thread. + * This method may block briefly if it needs to wake the poll. + * + * The callback may either be specified as a bare function pointer or as a smart + * pointer callback object. The smart pointer should be preferred because it is + * easier to avoid races when the callback is removed from a different thread. + * See removeFd() for details. + */ + int addFd(int fd, int ident, int events, Looper_callbackFunc callback, void* data); + int addFd(int fd, int ident, int events, const sp& callback, void* data); + + /** + * Removes a previously added file descriptor from the looper. + * + * When this method returns, it is safe to close the file descriptor since the looper + * will no longer have a reference to it. However, it is possible for the callback to + * already be running or for it to run one last time if the file descriptor was already + * signalled. Calling code is responsible for ensuring that this case is safely handled. + * For example, if the callback takes care of removing itself during its own execution either + * by returning 0 or by calling this method, then it can be guaranteed to not be invoked + * again at any later time unless registered anew. + * + * A simple way to avoid this problem is to use the version of addFd() that takes + * a sp instead of a bare function pointer. The LooperCallback will + * be released at the appropriate time by the Looper. + * + * Returns 1 if the file descriptor was removed, 0 if none was previously registered. + * + * This method can be called on any thread. + * This method may block briefly if it needs to wake the poll. + */ + int removeFd(int fd); + + /** + * Enqueues a message to be processed by the specified handler. + * + * The handler must not be null. + * This method can be called on any thread. + */ + void sendMessage(const sp& handler, const Message& message); + + /** + * Enqueues a message to be processed by the specified handler after all pending messages + * after the specified delay. + * + * The time delay is specified in uptime nanoseconds. + * The handler must not be null. + * This method can be called on any thread. + */ + void sendMessageDelayed(nsecs_t uptimeDelay, const sp& handler, + const Message& message); + + /** + * Enqueues a message to be processed by the specified handler after all pending messages + * at the specified time. + * + * The time is specified in uptime nanoseconds. + * The handler must not be null. + * This method can be called on any thread. + */ + void sendMessageAtTime(nsecs_t uptime, const sp& handler, + const Message& message); + + /** + * Removes all messages for the specified handler from the queue. + * + * The handler must not be null. + * This method can be called on any thread. + */ + void removeMessages(const sp& handler); + + /** + * Removes all messages of a particular type for the specified handler from the queue. + * + * The handler must not be null. + * This method can be called on any thread. + */ + void removeMessages(const sp& handler, int what); + + /** + * Returns whether this looper's thread is currently polling for more work to do. + * This is a good signal that the loop is still alive rather than being stuck + * handling a callback. Note that this method is intrinsically racy, since the + * state of the loop can change before you get the result back. + */ + bool isPolling() const; + + /** + * Prepares a looper associated with the calling thread, and returns it. + * If the thread already has a looper, it is returned. Otherwise, a new + * one is created, associated with the thread, and returned. + * + * The opts may be PREPARE_ALLOW_NON_CALLBACKS or 0. + */ + static sp prepare(int opts); + + /** + * Sets the given looper to be associated with the calling thread. + * If another looper is already associated with the thread, it is replaced. + * + * If "looper" is NULL, removes the currently associated looper. + */ + static void setForThread(const sp& looper); + + /** + * Returns the looper associated with the calling thread, or NULL if + * there is not one. + */ + static sp getForThread(); + +private: + struct Request { + int fd; + int ident; + int events; + int seq; + sp callback; + void* data; + + void initEventItem(struct epoll_event* eventItem) const; + }; + + struct Response { + int events; + Request request; + }; + + struct MessageEnvelope { + MessageEnvelope() : uptime(0) { } + + MessageEnvelope(nsecs_t uptime, const sp handler, + const Message& message) : uptime(uptime), handler(handler), message(message) { + } + + nsecs_t uptime; + sp handler; + Message message; + }; + + const bool mAllowNonCallbacks; // immutable + + int mWakeEventFd; // immutable + Mutex mLock; + + Vector mMessageEnvelopes; // guarded by mLock + bool mSendingMessage; // guarded by mLock + + // Whether we are currently waiting for work. Not protected by a lock, + // any use of it is racy anyway. + volatile bool mPolling; + + int mEpollFd; // guarded by mLock but only modified on the looper thread + bool mEpollRebuildRequired; // guarded by mLock + + // Locked list of file descriptor monitoring requests. + KeyedVector mRequests; // guarded by mLock + int mNextRequestSeq; + + // This state is only used privately by pollOnce and does not require a lock since + // it runs on a single thread. + Vector mResponses; + size_t mResponseIndex; + nsecs_t mNextMessageUptime; // set to LLONG_MAX when none + + int pollInner(int timeoutMillis); + int removeFd(int fd, int seq); + void awoken(); + void pushResponse(int events, const Request& request); + void rebuildEpollLocked(); + void scheduleEpollRebuildLocked(); + + static void initTLSKey(); + static void threadDestructor(void *st); + static void initEpollEvent(struct epoll_event* eventItem); +}; + +} // namespace android + +#endif // UTILS_LOOPER_H diff --git a/third_party/android_system_core/include/utils/LruCache.h b/third_party/android_system_core/include/utils/LruCache.h new file mode 100644 index 00000000000000..cd9d7f94a024c0 --- /dev/null +++ b/third_party/android_system_core/include/utils/LruCache.h @@ -0,0 +1,250 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_LRU_CACHE_H +#define ANDROID_UTILS_LRU_CACHE_H + +#include +#include + +namespace android { + +/** + * GenerationCache callback used when an item is removed + */ +template +class OnEntryRemoved { +public: + virtual ~OnEntryRemoved() { }; + virtual void operator()(EntryKey& key, EntryValue& value) = 0; +}; // class OnEntryRemoved + +template +class LruCache { +public: + explicit LruCache(uint32_t maxCapacity); + + enum Capacity { + kUnlimitedCapacity, + }; + + void setOnEntryRemovedListener(OnEntryRemoved* listener); + size_t size() const; + const TValue& get(const TKey& key); + bool put(const TKey& key, const TValue& value); + bool remove(const TKey& key); + bool removeOldest(); + void clear(); + const TValue& peekOldestValue(); + + class Iterator { + public: + Iterator(const LruCache& cache): mCache(cache), mIndex(-1) { + } + + bool next() { + mIndex = mCache.mTable->next(mIndex); + return (ssize_t)mIndex != -1; + } + + size_t index() const { + return mIndex; + } + + const TValue& value() const { + return mCache.mTable->entryAt(mIndex).value; + } + + const TKey& key() const { + return mCache.mTable->entryAt(mIndex).key; + } + private: + const LruCache& mCache; + size_t mIndex; + }; + +private: + LruCache(const LruCache& that); // disallow copy constructor + + struct Entry { + TKey key; + TValue value; + Entry* parent; + Entry* child; + + Entry(TKey key_, TValue value_) : key(key_), value(value_), parent(NULL), child(NULL) { + } + const TKey& getKey() const { return key; } + }; + + void attachToCache(Entry& entry); + void detachFromCache(Entry& entry); + void rehash(size_t newCapacity); + + UniquePtr > mTable; + OnEntryRemoved* mListener; + Entry* mOldest; + Entry* mYoungest; + uint32_t mMaxCapacity; + TValue mNullValue; +}; + +// Implementation is here, because it's fully templated +template +LruCache::LruCache(uint32_t maxCapacity) + : mTable(new BasicHashtable) + , mListener(NULL) + , mOldest(NULL) + , mYoungest(NULL) + , mMaxCapacity(maxCapacity) + , mNullValue(NULL) { +}; + +template +void LruCache::setOnEntryRemovedListener(OnEntryRemoved* listener) { + mListener = listener; +} + +template +size_t LruCache::size() const { + return mTable->size(); +} + +template +const TValue& LruCache::get(const TKey& key) { + hash_t hash = hash_type(key); + ssize_t index = mTable->find(-1, hash, key); + if (index == -1) { + return mNullValue; + } + Entry& entry = mTable->editEntryAt(index); + detachFromCache(entry); + attachToCache(entry); + return entry.value; +} + +template +bool LruCache::put(const TKey& key, const TValue& value) { + if (mMaxCapacity != kUnlimitedCapacity && size() >= mMaxCapacity) { + removeOldest(); + } + + hash_t hash = hash_type(key); + ssize_t index = mTable->find(-1, hash, key); + if (index >= 0) { + return false; + } + if (!mTable->hasMoreRoom()) { + rehash(mTable->capacity() * 2); + } + + // Would it be better to initialize a blank entry and assign key, value? + Entry initEntry(key, value); + index = mTable->add(hash, initEntry); + Entry& entry = mTable->editEntryAt(index); + attachToCache(entry); + return true; +} + +template +bool LruCache::remove(const TKey& key) { + hash_t hash = hash_type(key); + ssize_t index = mTable->find(-1, hash, key); + if (index < 0) { + return false; + } + Entry& entry = mTable->editEntryAt(index); + if (mListener) { + (*mListener)(entry.key, entry.value); + } + detachFromCache(entry); + mTable->removeAt(index); + return true; +} + +template +bool LruCache::removeOldest() { + if (mOldest != NULL) { + return remove(mOldest->key); + // TODO: should probably abort if false + } + return false; +} + +template +const TValue& LruCache::peekOldestValue() { + if (mOldest) { + return mOldest->value; + } + return mNullValue; +} + +template +void LruCache::clear() { + if (mListener) { + for (Entry* p = mOldest; p != NULL; p = p->child) { + (*mListener)(p->key, p->value); + } + } + mYoungest = NULL; + mOldest = NULL; + mTable->clear(); +} + +template +void LruCache::attachToCache(Entry& entry) { + if (mYoungest == NULL) { + mYoungest = mOldest = &entry; + } else { + entry.parent = mYoungest; + mYoungest->child = &entry; + mYoungest = &entry; + } +} + +template +void LruCache::detachFromCache(Entry& entry) { + if (entry.parent != NULL) { + entry.parent->child = entry.child; + } else { + mOldest = entry.child; + } + if (entry.child != NULL) { + entry.child->parent = entry.parent; + } else { + mYoungest = entry.parent; + } + + entry.parent = NULL; + entry.child = NULL; +} + +template +void LruCache::rehash(size_t newCapacity) { + UniquePtr > oldTable(mTable.release()); + Entry* oldest = mOldest; + + mOldest = NULL; + mYoungest = NULL; + mTable.reset(new BasicHashtable(newCapacity)); + for (Entry* p = oldest; p != NULL; p = p->child) { + put(p->key, p->value); + } +} + +} + +#endif // ANDROID_UTILS_LRU_CACHE_H diff --git a/third_party/android_system_core/include/utils/Mutex.h b/third_party/android_system_core/include/utils/Mutex.h new file mode 100644 index 00000000000000..757519b0860c23 --- /dev/null +++ b/third_party/android_system_core/include/utils/Mutex.h @@ -0,0 +1,157 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_MUTEX_H +#define _LIBS_UTILS_MUTEX_H + +#include +#include +#include + +#if !defined(_WIN32) +# include +#endif + +#include +#include + +// --------------------------------------------------------------------------- +namespace android { +// --------------------------------------------------------------------------- + +class Condition; + +/* + * Simple mutex class. The implementation is system-dependent. + * + * The mutex must be unlocked by the thread that locked it. They are not + * recursive, i.e. the same thread can't lock it multiple times. + */ +class Mutex { +public: + enum { + PRIVATE = 0, + SHARED = 1 + }; + + Mutex(); + Mutex(const char* name); + Mutex(int type, const char* name = NULL); + ~Mutex(); + + // lock or unlock the mutex + status_t lock(); + void unlock(); + + // lock if possible; returns 0 on success, error otherwise + status_t tryLock(); + +#if HAVE_ANDROID_OS + // lock the mutex, but don't wait longer than timeoutMilliseconds. + // Returns 0 on success, TIMED_OUT for failure due to timeout expiration. + // + // OSX doesn't have pthread_mutex_timedlock() or equivalent. To keep + // capabilities consistent across host OSes, this method is only available + // when building Android binaries. + status_t timedLock(nsecs_t timeoutMilliseconds); +#endif + + // Manages the mutex automatically. It'll be locked when Autolock is + // constructed and released when Autolock goes out of scope. + class Autolock { + public: + inline Autolock(Mutex& mutex) : mLock(mutex) { mLock.lock(); } + inline Autolock(Mutex* mutex) : mLock(*mutex) { mLock.lock(); } + inline ~Autolock() { mLock.unlock(); } + private: + Mutex& mLock; + }; + +private: + friend class Condition; + + // A mutex cannot be copied + Mutex(const Mutex&); + Mutex& operator = (const Mutex&); + +#if !defined(_WIN32) + pthread_mutex_t mMutex; +#else + void _init(); + void* mState; +#endif +}; + +// --------------------------------------------------------------------------- + +#if !defined(_WIN32) + +inline Mutex::Mutex() { + pthread_mutex_init(&mMutex, NULL); +} +inline Mutex::Mutex(__attribute__((unused)) const char* name) { + pthread_mutex_init(&mMutex, NULL); +} +inline Mutex::Mutex(int type, __attribute__((unused)) const char* name) { + if (type == SHARED) { + pthread_mutexattr_t attr; + pthread_mutexattr_init(&attr); + pthread_mutexattr_setpshared(&attr, PTHREAD_PROCESS_SHARED); + pthread_mutex_init(&mMutex, &attr); + pthread_mutexattr_destroy(&attr); + } else { + pthread_mutex_init(&mMutex, NULL); + } +} +inline Mutex::~Mutex() { + pthread_mutex_destroy(&mMutex); +} +inline status_t Mutex::lock() { + return -pthread_mutex_lock(&mMutex); +} +inline void Mutex::unlock() { + pthread_mutex_unlock(&mMutex); +} +inline status_t Mutex::tryLock() { + return -pthread_mutex_trylock(&mMutex); +} +#if HAVE_ANDROID_OS +inline status_t Mutex::timedLock(nsecs_t timeoutNs) { + const struct timespec ts = { + /* .tv_sec = */ static_cast(timeoutNs / 1000000000), + /* .tv_nsec = */ static_cast(timeoutNs % 1000000000), + }; + return -pthread_mutex_timedlock(&mMutex, &ts); +} +#endif + +#endif // !defined(_WIN32) + +// --------------------------------------------------------------------------- + +/* + * Automatic mutex. Declare one of these at the top of a function. + * When the function returns, it will go out of scope, and release the + * mutex. + */ + +typedef Mutex::Autolock AutoMutex; + +// --------------------------------------------------------------------------- +}; // namespace android +// --------------------------------------------------------------------------- + +#endif // _LIBS_UTILS_MUTEX_H diff --git a/third_party/android_system_core/include/utils/NativeHandle.h b/third_party/android_system_core/include/utils/NativeHandle.h new file mode 100644 index 00000000000000..b82516879ad474 --- /dev/null +++ b/third_party/android_system_core/include/utils/NativeHandle.h @@ -0,0 +1,56 @@ +/* + * Copyright 2014 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_NATIVE_HANDLE_H +#define ANDROID_NATIVE_HANDLE_H + +#include +#include + +typedef struct native_handle native_handle_t; + +namespace android { + +class NativeHandle: public LightRefBase { +public: + // Create a refcounted wrapper around a native_handle_t, and declare + // whether the wrapper owns the handle (so that it should clean up the + // handle upon destruction) or not. + // If handle is NULL, no NativeHandle will be created. + static sp create(native_handle_t* handle, bool ownsHandle); + + const native_handle_t* handle() const { + return mHandle; + } + +private: + // for access to the destructor + friend class LightRefBase; + + NativeHandle(native_handle_t* handle, bool ownsHandle); + virtual ~NativeHandle(); + + native_handle_t* mHandle; + bool mOwnsHandle; + + // non-copyable + NativeHandle(const NativeHandle&); + NativeHandle& operator=(const NativeHandle&); +}; + +} // namespace android + +#endif // ANDROID_NATIVE_HANDLE_H diff --git a/third_party/android_system_core/include/utils/Printer.h b/third_party/android_system_core/include/utils/Printer.h new file mode 100644 index 00000000000000..bb6628767ca893 --- /dev/null +++ b/third_party/android_system_core/include/utils/Printer.h @@ -0,0 +1,119 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_PRINTER_H +#define ANDROID_PRINTER_H + +#include + +namespace android { + +// Interface for printing to an arbitrary data stream +class Printer { +public: + // Print a new line specified by 'string'. \n is appended automatically. + // -- Assumes that the string has no new line in it. + virtual void printLine(const char* string = "") = 0; + + // Print a new line specified by the format string. \n is appended automatically. + // -- Assumes that the resulting string has no new line in it. + virtual void printFormatLine(const char* format, ...) __attribute__((format (printf, 2, 3))); + +protected: + Printer(); + virtual ~Printer(); +}; // class Printer + +// Print to logcat +class LogPrinter : public Printer { +public: + // Create a printer using the specified logcat and log priority + // - Unless ignoreBlankLines is false, print blank lines to logcat + // (Note that the default ALOG behavior is to ignore blank lines) + LogPrinter(const char* logtag, + android_LogPriority priority = ANDROID_LOG_DEBUG, + const char* prefix = 0, + bool ignoreBlankLines = false); + + // Print the specified line to logcat. No \n at the end is necessary. + virtual void printLine(const char* string); + +private: + void printRaw(const char* string); + + const char* mLogTag; + android_LogPriority mPriority; + const char* mPrefix; + bool mIgnoreBlankLines; +}; // class LogPrinter + +// Print to a file descriptor +class FdPrinter : public Printer { +public: + // Create a printer using the specified file descriptor. + // - Each line will be prefixed with 'indent' number of blank spaces. + // - In addition, each line will be prefixed with the 'prefix' string. + FdPrinter(int fd, unsigned int indent = 0, const char* prefix = 0); + + // Print the specified line to the file descriptor. \n is appended automatically. + virtual void printLine(const char* string); + +private: + enum { + MAX_FORMAT_STRING = 20, + }; + + int mFd; + unsigned int mIndent; + const char* mPrefix; + char mFormatString[MAX_FORMAT_STRING]; +}; // class FdPrinter + +class String8; + +// Print to a String8 +class String8Printer : public Printer { +public: + // Create a printer using the specified String8 as the target. + // - In addition, each line will be prefixed with the 'prefix' string. + // - target's memory lifetime must be a superset of this String8Printer. + String8Printer(String8* target, const char* prefix = 0); + + // Append the specified line to the String8. \n is appended automatically. + virtual void printLine(const char* string); + +private: + String8* mTarget; + const char* mPrefix; +}; // class String8Printer + +// Print to an existing Printer by adding a prefix to each line +class PrefixPrinter : public Printer { +public: + // Create a printer using the specified printer as the target. + PrefixPrinter(Printer& printer, const char* prefix); + + // Print the line (prefixed with prefix) using the printer. + virtual void printLine(const char* string); + +private: + Printer& mPrinter; + const char* mPrefix; +}; + +}; // namespace android + +#endif // ANDROID_PRINTER_H diff --git a/third_party/android_system_core/include/utils/ProcessCallStack.h b/third_party/android_system_core/include/utils/ProcessCallStack.h new file mode 100644 index 00000000000000..32458b8b14979a --- /dev/null +++ b/third_party/android_system_core/include/utils/ProcessCallStack.h @@ -0,0 +1,79 @@ +/* + * Copyright (C) 2013 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_PROCESS_CALLSTACK_H +#define ANDROID_PROCESS_CALLSTACK_H + +#include +#include +#include +#include + +#include +#include + +namespace android { + +class Printer; + +// Collect/print the call stack (function, file, line) traces for all threads in a process. +class ProcessCallStack { +public: + // Create an empty call stack. No-op. + ProcessCallStack(); + // Copy the existing process callstack (no other side effects). + ProcessCallStack(const ProcessCallStack& rhs); + ~ProcessCallStack(); + + // Immediately collect the stack traces for all threads. + void update(); + + // Print all stack traces to the log using the supplied logtag. + void log(const char* logtag, android_LogPriority priority = ANDROID_LOG_DEBUG, + const char* prefix = 0) const; + + // Dump all stack traces to the specified file descriptor. + void dump(int fd, int indent = 0, const char* prefix = 0) const; + + // Return a string (possibly very long) containing all the stack traces. + String8 toString(const char* prefix = 0) const; + + // Dump a serialized representation of all the stack traces to the specified printer. + void print(Printer& printer) const; + + // Get the number of threads whose stack traces were collected. + size_t size() const; + +private: + void printInternal(Printer& printer, Printer& csPrinter) const; + + // Reset the process's stack frames and metadata. + void clear(); + + struct ThreadInfo { + CallStack callStack; + String8 threadName; + }; + + // tid -> ThreadInfo + KeyedVector mThreadMap; + // Time that update() was last called + struct tm mTimeUpdated; +}; + +}; // namespace android + +#endif // ANDROID_PROCESS_CALLSTACK_H diff --git a/third_party/android_system_core/include/utils/PropertyMap.h b/third_party/android_system_core/include/utils/PropertyMap.h new file mode 100644 index 00000000000000..a9e674f9afb1f1 --- /dev/null +++ b/third_party/android_system_core/include/utils/PropertyMap.h @@ -0,0 +1,106 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _UTILS_PROPERTY_MAP_H +#define _UTILS_PROPERTY_MAP_H + +#include +#include +#include +#include + +namespace android { + +/* + * Provides a mechanism for passing around string-based property key / value pairs + * and loading them from property files. + * + * The property files have the following simple structure: + * + * # Comment + * key = value + * + * Keys and values are any sequence of printable ASCII characters. + * The '=' separates the key from the value. + * The key and value may not contain whitespace. + * + * The '\' character is reserved for escape sequences and is not currently supported. + * The '"" character is reserved for quoting and is not currently supported. + * Files that contain the '\' or '"' character will fail to parse. + * + * The file must not contain duplicate keys. + * + * TODO Support escape sequences and quoted values when needed. + */ +class PropertyMap { +public: + /* Creates an empty property map. */ + PropertyMap(); + ~PropertyMap(); + + /* Clears the property map. */ + void clear(); + + /* Adds a property. + * Replaces the property with the same key if it is already present. + */ + void addProperty(const String8& key, const String8& value); + + /* Returns true if the property map contains the specified key. */ + bool hasProperty(const String8& key) const; + + /* Gets the value of a property and parses it. + * Returns true and sets outValue if the key was found and its value was parsed successfully. + * Otherwise returns false and does not modify outValue. (Also logs a warning.) + */ + bool tryGetProperty(const String8& key, String8& outValue) const; + bool tryGetProperty(const String8& key, bool& outValue) const; + bool tryGetProperty(const String8& key, int32_t& outValue) const; + bool tryGetProperty(const String8& key, float& outValue) const; + + /* Adds all values from the specified property map. */ + void addAll(const PropertyMap* map); + + /* Gets the underlying property map. */ + inline const KeyedVector& getProperties() const { return mProperties; } + + /* Loads a property map from a file. */ + static status_t load(const String8& filename, PropertyMap** outMap); + +private: + class Parser { + PropertyMap* mMap; + Tokenizer* mTokenizer; + + public: + Parser(PropertyMap* map, Tokenizer* tokenizer); + ~Parser(); + status_t parse(); + + private: + status_t parseType(); + status_t parseKey(); + status_t parseKeyProperty(); + status_t parseModifier(const String8& token, int32_t* outMetaState); + status_t parseCharacterLiteral(char16_t* outCharacter); + }; + + KeyedVector mProperties; +}; + +} // namespace android + +#endif // _UTILS_PROPERTY_MAP_H diff --git a/third_party/android_system_core/include/utils/RWLock.h b/third_party/android_system_core/include/utils/RWLock.h new file mode 100644 index 00000000000000..e743b1c8ced05a --- /dev/null +++ b/third_party/android_system_core/include/utils/RWLock.h @@ -0,0 +1,126 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_RWLOCK_H +#define _LIBS_UTILS_RWLOCK_H + +#include +#include + +#if !defined(_WIN32) +# include +#endif + +#include +#include + +// --------------------------------------------------------------------------- +namespace android { +// --------------------------------------------------------------------------- + +#if !defined(_WIN32) + +/* + * Simple mutex class. The implementation is system-dependent. + * + * The mutex must be unlocked by the thread that locked it. They are not + * recursive, i.e. the same thread can't lock it multiple times. + */ +class RWLock { +public: + enum { + PRIVATE = 0, + SHARED = 1 + }; + + RWLock(); + RWLock(const char* name); + RWLock(int type, const char* name = NULL); + ~RWLock(); + + status_t readLock(); + status_t tryReadLock(); + status_t writeLock(); + status_t tryWriteLock(); + void unlock(); + + class AutoRLock { + public: + inline AutoRLock(RWLock& rwlock) : mLock(rwlock) { mLock.readLock(); } + inline ~AutoRLock() { mLock.unlock(); } + private: + RWLock& mLock; + }; + + class AutoWLock { + public: + inline AutoWLock(RWLock& rwlock) : mLock(rwlock) { mLock.writeLock(); } + inline ~AutoWLock() { mLock.unlock(); } + private: + RWLock& mLock; + }; + +private: + // A RWLock cannot be copied + RWLock(const RWLock&); + RWLock& operator = (const RWLock&); + + pthread_rwlock_t mRWLock; +}; + +inline RWLock::RWLock() { + pthread_rwlock_init(&mRWLock, NULL); +} +inline RWLock::RWLock(__attribute__((unused)) const char* name) { + pthread_rwlock_init(&mRWLock, NULL); +} +inline RWLock::RWLock(int type, __attribute__((unused)) const char* name) { + if (type == SHARED) { + pthread_rwlockattr_t attr; + pthread_rwlockattr_init(&attr); + pthread_rwlockattr_setpshared(&attr, PTHREAD_PROCESS_SHARED); + pthread_rwlock_init(&mRWLock, &attr); + pthread_rwlockattr_destroy(&attr); + } else { + pthread_rwlock_init(&mRWLock, NULL); + } +} +inline RWLock::~RWLock() { + pthread_rwlock_destroy(&mRWLock); +} +inline status_t RWLock::readLock() { + return -pthread_rwlock_rdlock(&mRWLock); +} +inline status_t RWLock::tryReadLock() { + return -pthread_rwlock_tryrdlock(&mRWLock); +} +inline status_t RWLock::writeLock() { + return -pthread_rwlock_wrlock(&mRWLock); +} +inline status_t RWLock::tryWriteLock() { + return -pthread_rwlock_trywrlock(&mRWLock); +} +inline void RWLock::unlock() { + pthread_rwlock_unlock(&mRWLock); +} + +#endif // !defined(_WIN32) + +// --------------------------------------------------------------------------- +}; // namespace android +// --------------------------------------------------------------------------- + +#endif // _LIBS_UTILS_RWLOCK_H diff --git a/third_party/android_system_core/include/utils/RefBase.h b/third_party/android_system_core/include/utils/RefBase.h new file mode 100644 index 00000000000000..eac6a78402378a --- /dev/null +++ b/third_party/android_system_core/include/utils/RefBase.h @@ -0,0 +1,555 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_REF_BASE_H +#define ANDROID_REF_BASE_H + +#include + +#include +#include +#include +#include + +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +class TextOutput; +TextOutput& printWeakPointer(TextOutput& to, const void* val); + +// --------------------------------------------------------------------------- + +#define COMPARE_WEAK(_op_) \ +inline bool operator _op_ (const sp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} \ +inline bool operator _op_ (const T* o) const { \ + return m_ptr _op_ o; \ +} \ +template \ +inline bool operator _op_ (const sp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} \ +template \ +inline bool operator _op_ (const U* o) const { \ + return m_ptr _op_ o; \ +} + +// --------------------------------------------------------------------------- + +class ReferenceRenamer { +protected: + // destructor is purposedly not virtual so we avoid code overhead from + // subclasses; we have to make it protected to guarantee that it + // cannot be called from this base class (and to make strict compilers + // happy). + ~ReferenceRenamer() { } +public: + virtual void operator()(size_t i) const = 0; +}; + +// --------------------------------------------------------------------------- + +class RefBase +{ +public: + void incStrong(const void* id) const; + void decStrong(const void* id) const; + + void forceIncStrong(const void* id) const; + + //! DEBUGGING ONLY: Get current strong ref count. + int32_t getStrongCount() const; + + class weakref_type + { + public: + RefBase* refBase() const; + + void incWeak(const void* id); + void decWeak(const void* id); + + // acquires a strong reference if there is already one. + bool attemptIncStrong(const void* id); + + // acquires a weak reference if there is already one. + // This is not always safe. see ProcessState.cpp and BpBinder.cpp + // for proper use. + bool attemptIncWeak(const void* id); + + //! DEBUGGING ONLY: Get current weak ref count. + int32_t getWeakCount() const; + + //! DEBUGGING ONLY: Print references held on object. + void printRefs() const; + + //! DEBUGGING ONLY: Enable tracking for this object. + // enable -- enable/disable tracking + // retain -- when tracking is enable, if true, then we save a stack trace + // for each reference and dereference; when retain == false, we + // match up references and dereferences and keep only the + // outstanding ones. + + void trackMe(bool enable, bool retain); + }; + + weakref_type* createWeak(const void* id) const; + + weakref_type* getWeakRefs() const; + + //! DEBUGGING ONLY: Print references held on object. + inline void printRefs() const { getWeakRefs()->printRefs(); } + + //! DEBUGGING ONLY: Enable tracking of object. + inline void trackMe(bool enable, bool retain) + { + getWeakRefs()->trackMe(enable, retain); + } + + typedef RefBase basetype; + +protected: + RefBase(); + virtual ~RefBase(); + + //! Flags for extendObjectLifetime() + enum { + OBJECT_LIFETIME_STRONG = 0x0000, + OBJECT_LIFETIME_WEAK = 0x0001, + OBJECT_LIFETIME_MASK = 0x0001 + }; + + void extendObjectLifetime(int32_t mode); + + //! Flags for onIncStrongAttempted() + enum { + FIRST_INC_STRONG = 0x0001 + }; + + virtual void onFirstRef(); + virtual void onLastStrongRef(const void* id); + virtual bool onIncStrongAttempted(uint32_t flags, const void* id); + virtual void onLastWeakRef(const void* id); + +private: + friend class weakref_type; + class weakref_impl; + + RefBase(const RefBase& o); + RefBase& operator=(const RefBase& o); + +private: + friend class ReferenceMover; + + static void renameRefs(size_t n, const ReferenceRenamer& renamer); + + static void renameRefId(weakref_type* ref, + const void* old_id, const void* new_id); + + static void renameRefId(RefBase* ref, + const void* old_id, const void* new_id); + + weakref_impl* const mRefs; +}; + +// --------------------------------------------------------------------------- + +template +class LightRefBase +{ +public: + inline LightRefBase() : mCount(0) { } + inline void incStrong(__attribute__((unused)) const void* id) const { + android_atomic_inc(&mCount); + } + inline void decStrong(__attribute__((unused)) const void* id) const { + if (android_atomic_dec(&mCount) == 1) { + delete static_cast(this); + } + } + //! DEBUGGING ONLY: Get current strong ref count. + inline int32_t getStrongCount() const { + return mCount; + } + + typedef LightRefBase basetype; + +protected: + inline ~LightRefBase() { } + +private: + friend class ReferenceMover; + inline static void renameRefs(size_t n, const ReferenceRenamer& renamer) { } + inline static void renameRefId(T* ref, + const void* old_id, const void* new_id) { } + +private: + mutable volatile int32_t mCount; +}; + +// This is a wrapper around LightRefBase that simply enforces a virtual +// destructor to eliminate the template requirement of LightRefBase +class VirtualLightRefBase : public LightRefBase { +public: + virtual ~VirtualLightRefBase() {} +}; + +// --------------------------------------------------------------------------- + +template +class wp +{ +public: + typedef typename RefBase::weakref_type weakref_type; + + inline wp() : m_ptr(0) { } + + wp(T* other); + wp(const wp& other); + wp(const sp& other); + template wp(U* other); + template wp(const sp& other); + template wp(const wp& other); + + ~wp(); + + // Assignment + + wp& operator = (T* other); + wp& operator = (const wp& other); + wp& operator = (const sp& other); + + template wp& operator = (U* other); + template wp& operator = (const wp& other); + template wp& operator = (const sp& other); + + void set_object_and_refs(T* other, weakref_type* refs); + + // promotion to sp + + sp promote() const; + + // Reset + + void clear(); + + // Accessors + + inline weakref_type* get_refs() const { return m_refs; } + + inline T* unsafe_get() const { return m_ptr; } + + // Operators + + COMPARE_WEAK(==) + COMPARE_WEAK(!=) + COMPARE_WEAK(>) + COMPARE_WEAK(<) + COMPARE_WEAK(<=) + COMPARE_WEAK(>=) + + inline bool operator == (const wp& o) const { + return (m_ptr == o.m_ptr) && (m_refs == o.m_refs); + } + template + inline bool operator == (const wp& o) const { + return m_ptr == o.m_ptr; + } + + inline bool operator > (const wp& o) const { + return (m_ptr == o.m_ptr) ? (m_refs > o.m_refs) : (m_ptr > o.m_ptr); + } + template + inline bool operator > (const wp& o) const { + return (m_ptr == o.m_ptr) ? (m_refs > o.m_refs) : (m_ptr > o.m_ptr); + } + + inline bool operator < (const wp& o) const { + return (m_ptr == o.m_ptr) ? (m_refs < o.m_refs) : (m_ptr < o.m_ptr); + } + template + inline bool operator < (const wp& o) const { + return (m_ptr == o.m_ptr) ? (m_refs < o.m_refs) : (m_ptr < o.m_ptr); + } + inline bool operator != (const wp& o) const { return m_refs != o.m_refs; } + template inline bool operator != (const wp& o) const { return !operator == (o); } + inline bool operator <= (const wp& o) const { return !operator > (o); } + template inline bool operator <= (const wp& o) const { return !operator > (o); } + inline bool operator >= (const wp& o) const { return !operator < (o); } + template inline bool operator >= (const wp& o) const { return !operator < (o); } + +private: + template friend class sp; + template friend class wp; + + T* m_ptr; + weakref_type* m_refs; +}; + +template +TextOutput& operator<<(TextOutput& to, const wp& val); + +#undef COMPARE_WEAK + +// --------------------------------------------------------------------------- +// No user serviceable parts below here. + +template +wp::wp(T* other) + : m_ptr(other) +{ + if (other) m_refs = other->createWeak(this); +} + +template +wp::wp(const wp& other) + : m_ptr(other.m_ptr), m_refs(other.m_refs) +{ + if (m_ptr) m_refs->incWeak(this); +} + +template +wp::wp(const sp& other) + : m_ptr(other.m_ptr) +{ + if (m_ptr) { + m_refs = m_ptr->createWeak(this); + } +} + +template template +wp::wp(U* other) + : m_ptr(other) +{ + if (other) m_refs = other->createWeak(this); +} + +template template +wp::wp(const wp& other) + : m_ptr(other.m_ptr) +{ + if (m_ptr) { + m_refs = other.m_refs; + m_refs->incWeak(this); + } +} + +template template +wp::wp(const sp& other) + : m_ptr(other.m_ptr) +{ + if (m_ptr) { + m_refs = m_ptr->createWeak(this); + } +} + +template +wp::~wp() +{ + if (m_ptr) m_refs->decWeak(this); +} + +template +wp& wp::operator = (T* other) +{ + weakref_type* newRefs = + other ? other->createWeak(this) : 0; + if (m_ptr) m_refs->decWeak(this); + m_ptr = other; + m_refs = newRefs; + return *this; +} + +template +wp& wp::operator = (const wp& other) +{ + weakref_type* otherRefs(other.m_refs); + T* otherPtr(other.m_ptr); + if (otherPtr) otherRefs->incWeak(this); + if (m_ptr) m_refs->decWeak(this); + m_ptr = otherPtr; + m_refs = otherRefs; + return *this; +} + +template +wp& wp::operator = (const sp& other) +{ + weakref_type* newRefs = + other != NULL ? other->createWeak(this) : 0; + T* otherPtr(other.m_ptr); + if (m_ptr) m_refs->decWeak(this); + m_ptr = otherPtr; + m_refs = newRefs; + return *this; +} + +template template +wp& wp::operator = (U* other) +{ + weakref_type* newRefs = + other ? other->createWeak(this) : 0; + if (m_ptr) m_refs->decWeak(this); + m_ptr = other; + m_refs = newRefs; + return *this; +} + +template template +wp& wp::operator = (const wp& other) +{ + weakref_type* otherRefs(other.m_refs); + U* otherPtr(other.m_ptr); + if (otherPtr) otherRefs->incWeak(this); + if (m_ptr) m_refs->decWeak(this); + m_ptr = otherPtr; + m_refs = otherRefs; + return *this; +} + +template template +wp& wp::operator = (const sp& other) +{ + weakref_type* newRefs = + other != NULL ? other->createWeak(this) : 0; + U* otherPtr(other.m_ptr); + if (m_ptr) m_refs->decWeak(this); + m_ptr = otherPtr; + m_refs = newRefs; + return *this; +} + +template +void wp::set_object_and_refs(T* other, weakref_type* refs) +{ + if (other) refs->incWeak(this); + if (m_ptr) m_refs->decWeak(this); + m_ptr = other; + m_refs = refs; +} + +template +sp wp::promote() const +{ + sp result; + if (m_ptr && m_refs->attemptIncStrong(&result)) { + result.set_pointer(m_ptr); + } + return result; +} + +template +void wp::clear() +{ + if (m_ptr) { + m_refs->decWeak(this); + m_ptr = 0; + } +} + +template +inline TextOutput& operator<<(TextOutput& to, const wp& val) +{ + return printWeakPointer(to, val.unsafe_get()); +} + +// --------------------------------------------------------------------------- + +// this class just serves as a namespace so TYPE::moveReferences can stay +// private. +class ReferenceMover { +public: + // it would be nice if we could make sure no extra code is generated + // for sp or wp when TYPE is a descendant of RefBase: + // Using a sp override doesn't work; it's a bit like we wanted + // a template template... + + template static inline + void move_references(sp* d, sp const* s, size_t n) { + + class Renamer : public ReferenceRenamer { + sp* d; + sp const* s; + virtual void operator()(size_t i) const { + // The id are known to be the sp<>'s this pointer + TYPE::renameRefId(d[i].get(), &s[i], &d[i]); + } + public: + Renamer(sp* d, sp const* s) : d(d), s(s) { } + virtual ~Renamer() { } + }; + + memmove(d, s, n*sizeof(sp)); + TYPE::renameRefs(n, Renamer(d, s)); + } + + + template static inline + void move_references(wp* d, wp const* s, size_t n) { + + class Renamer : public ReferenceRenamer { + wp* d; + wp const* s; + virtual void operator()(size_t i) const { + // The id are known to be the wp<>'s this pointer + TYPE::renameRefId(d[i].get_refs(), &s[i], &d[i]); + } + public: + Renamer(wp* d, wp const* s) : d(d), s(s) { } + virtual ~Renamer() { } + }; + + memmove(d, s, n*sizeof(wp)); + TYPE::renameRefs(n, Renamer(d, s)); + } +}; + +// specialization for moving sp<> and wp<> types. +// these are used by the [Sorted|Keyed]Vector<> implementations +// sp<> and wp<> need to be handled specially, because they do not +// have trivial copy operation in the general case (see RefBase.cpp +// when DEBUG ops are enabled), but can be implemented very +// efficiently in most cases. + +template inline +void move_forward_type(sp* d, sp const* s, size_t n) { + ReferenceMover::move_references(d, s, n); +} + +template inline +void move_backward_type(sp* d, sp const* s, size_t n) { + ReferenceMover::move_references(d, s, n); +} + +template inline +void move_forward_type(wp* d, wp const* s, size_t n) { + ReferenceMover::move_references(d, s, n); +} + +template inline +void move_backward_type(wp* d, wp const* s, size_t n) { + ReferenceMover::move_references(d, s, n); +} + + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_REF_BASE_H diff --git a/third_party/android_system_core/include/utils/SharedBuffer.h b/third_party/android_system_core/include/utils/SharedBuffer.h new file mode 100644 index 00000000000000..b6709537e69358 --- /dev/null +++ b/third_party/android_system_core/include/utils/SharedBuffer.h @@ -0,0 +1,137 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_SHARED_BUFFER_H +#define ANDROID_SHARED_BUFFER_H + +#include +#include + +// --------------------------------------------------------------------------- + +namespace android { + +class SharedBuffer +{ +public: + + /* flags to use with release() */ + enum { + eKeepStorage = 0x00000001 + }; + + /*! allocate a buffer of size 'size' and acquire() it. + * call release() to free it. + */ + static SharedBuffer* alloc(size_t size); + + /*! free the memory associated with the SharedBuffer. + * Fails if there are any users associated with this SharedBuffer. + * In other words, the buffer must have been release by all its + * users. + */ + static ssize_t dealloc(const SharedBuffer* released); + + //! access the data for read + inline const void* data() const; + + //! access the data for read/write + inline void* data(); + + //! get size of the buffer + inline size_t size() const; + + //! get back a SharedBuffer object from its data + static inline SharedBuffer* bufferFromData(void* data); + + //! get back a SharedBuffer object from its data + static inline const SharedBuffer* bufferFromData(const void* data); + + //! get the size of a SharedBuffer object from its data + static inline size_t sizeFromData(const void* data); + + //! edit the buffer (get a writtable, or non-const, version of it) + SharedBuffer* edit() const; + + //! edit the buffer, resizing if needed + SharedBuffer* editResize(size_t size) const; + + //! like edit() but fails if a copy is required + SharedBuffer* attemptEdit() const; + + //! resize and edit the buffer, loose it's content. + SharedBuffer* reset(size_t size) const; + + //! acquire/release a reference on this buffer + void acquire() const; + + /*! release a reference on this buffer, with the option of not + * freeing the memory associated with it if it was the last reference + * returns the previous reference count + */ + int32_t release(uint32_t flags = 0) const; + + //! returns wether or not we're the only owner + inline bool onlyOwner() const; + + +private: + inline SharedBuffer() { } + inline ~SharedBuffer() { } + SharedBuffer(const SharedBuffer&); + SharedBuffer& operator = (const SharedBuffer&); + + // 16 bytes. must be sized to preserve correct alignment. + mutable int32_t mRefs; + size_t mSize; + uint32_t mReserved[2]; +}; + +// --------------------------------------------------------------------------- + +const void* SharedBuffer::data() const { + return this + 1; +} + +void* SharedBuffer::data() { + return this + 1; +} + +size_t SharedBuffer::size() const { + return mSize; +} + +SharedBuffer* SharedBuffer::bufferFromData(void* data) { + return data ? static_cast(data)-1 : 0; +} + +const SharedBuffer* SharedBuffer::bufferFromData(const void* data) { + return data ? static_cast(data)-1 : 0; +} + +size_t SharedBuffer::sizeFromData(const void* data) { + return data ? bufferFromData(data)->mSize : 0; +} + +bool SharedBuffer::onlyOwner() const { + return (mRefs == 1); +} + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_VECTOR_H diff --git a/third_party/android_system_core/include/utils/Singleton.h b/third_party/android_system_core/include/utils/Singleton.h new file mode 100644 index 00000000000000..ffc03cb5d641a4 --- /dev/null +++ b/third_party/android_system_core/include/utils/Singleton.h @@ -0,0 +1,78 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_SINGLETON_H +#define ANDROID_UTILS_SINGLETON_H + +#include +#include +#include +#include + +namespace android { +// --------------------------------------------------------------------------- + +template +class ANDROID_API Singleton +{ +public: + static TYPE& getInstance() { + Mutex::Autolock _l(sLock); + TYPE* instance = sInstance; + if (instance == 0) { + instance = new TYPE(); + sInstance = instance; + } + return *instance; + } + + static bool hasInstance() { + Mutex::Autolock _l(sLock); + return sInstance != 0; + } + +protected: + ~Singleton() { }; + Singleton() { }; + +private: + Singleton(const Singleton&); + Singleton& operator = (const Singleton&); + static Mutex sLock; + static TYPE* sInstance; +}; + +/* + * use ANDROID_SINGLETON_STATIC_INSTANCE(TYPE) in your implementation file + * (eg: .cpp) to create the static instance of Singleton<>'s attributes, + * and avoid to have a copy of them in each compilation units Singleton + * is used. + * NOTE: we use a version of Mutex ctor that takes a parameter, because + * for some unknown reason using the default ctor doesn't emit the variable! + */ + +#define ANDROID_SINGLETON_STATIC_INSTANCE(TYPE) \ + template<> ::android::Mutex \ + (::android::Singleton< TYPE >::sLock)(::android::Mutex::PRIVATE); \ + template<> TYPE* ::android::Singleton< TYPE >::sInstance(0); \ + template class ::android::Singleton< TYPE >; + + +// --------------------------------------------------------------------------- +}; // namespace android + +#endif // ANDROID_UTILS_SINGLETON_H + diff --git a/third_party/android_system_core/include/utils/SortedVector.h b/third_party/android_system_core/include/utils/SortedVector.h new file mode 100644 index 00000000000000..2d3e82a7c0140f --- /dev/null +++ b/third_party/android_system_core/include/utils/SortedVector.h @@ -0,0 +1,282 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_SORTED_VECTOR_H +#define ANDROID_SORTED_VECTOR_H + +#include +#include +#include + +#include + +#include +#include +#include + +// --------------------------------------------------------------------------- + +namespace android { + +template +class SortedVector : private SortedVectorImpl +{ + friend class Vector; + +public: + typedef TYPE value_type; + + /*! + * Constructors and destructors + */ + + SortedVector(); + SortedVector(const SortedVector& rhs); + virtual ~SortedVector(); + + /*! copy operator */ + const SortedVector& operator = (const SortedVector& rhs) const; + SortedVector& operator = (const SortedVector& rhs); + + /* + * empty the vector + */ + + inline void clear() { VectorImpl::clear(); } + + /*! + * vector stats + */ + + //! returns number of items in the vector + inline size_t size() const { return VectorImpl::size(); } + //! returns whether or not the vector is empty + inline bool isEmpty() const { return VectorImpl::isEmpty(); } + //! returns how many items can be stored without reallocating the backing store + inline size_t capacity() const { return VectorImpl::capacity(); } + //! sets the capacity. capacity can never be reduced less than size() + inline ssize_t setCapacity(size_t size) { return VectorImpl::setCapacity(size); } + + /*! + * C-style array access + */ + + //! read-only C-style access + inline const TYPE* array() const; + + //! read-write C-style access. BE VERY CAREFUL when modifying the array + //! you must keep it sorted! You usually don't use this function. + TYPE* editArray(); + + //! finds the index of an item + ssize_t indexOf(const TYPE& item) const; + + //! finds where this item should be inserted + size_t orderOf(const TYPE& item) const; + + + /*! + * accessors + */ + + //! read-only access to an item at a given index + inline const TYPE& operator [] (size_t index) const; + //! alternate name for operator [] + inline const TYPE& itemAt(size_t index) const; + //! stack-usage of the vector. returns the top of the stack (last element) + const TYPE& top() const; + + /*! + * modifying the array + */ + + //! add an item in the right place (and replace the one that is there) + ssize_t add(const TYPE& item); + + //! editItemAt() MUST NOT change the order of this item + TYPE& editItemAt(size_t index) { + return *( static_cast(VectorImpl::editItemLocation(index)) ); + } + + //! merges a vector into this one + ssize_t merge(const Vector& vector); + ssize_t merge(const SortedVector& vector); + + //! removes an item + ssize_t remove(const TYPE&); + + //! remove several items + inline ssize_t removeItemsAt(size_t index, size_t count = 1); + //! remove one item + inline ssize_t removeAt(size_t index) { return removeItemsAt(index); } + +protected: + virtual void do_construct(void* storage, size_t num) const; + virtual void do_destroy(void* storage, size_t num) const; + virtual void do_copy(void* dest, const void* from, size_t num) const; + virtual void do_splat(void* dest, const void* item, size_t num) const; + virtual void do_move_forward(void* dest, const void* from, size_t num) const; + virtual void do_move_backward(void* dest, const void* from, size_t num) const; + virtual int do_compare(const void* lhs, const void* rhs) const; +}; + +// SortedVector can be trivially moved using memcpy() because moving does not +// require any change to the underlying SharedBuffer contents or reference count. +template struct trait_trivial_move > { enum { value = true }; }; + +// --------------------------------------------------------------------------- +// No user serviceable parts from here... +// --------------------------------------------------------------------------- + +template inline +SortedVector::SortedVector() + : SortedVectorImpl(sizeof(TYPE), + ((traits::has_trivial_ctor ? HAS_TRIVIAL_CTOR : 0) + |(traits::has_trivial_dtor ? HAS_TRIVIAL_DTOR : 0) + |(traits::has_trivial_copy ? HAS_TRIVIAL_COPY : 0)) + ) +{ +} + +template inline +SortedVector::SortedVector(const SortedVector& rhs) + : SortedVectorImpl(rhs) { +} + +template inline +SortedVector::~SortedVector() { + finish_vector(); +} + +template inline +SortedVector& SortedVector::operator = (const SortedVector& rhs) { + SortedVectorImpl::operator = (rhs); + return *this; +} + +template inline +const SortedVector& SortedVector::operator = (const SortedVector& rhs) const { + SortedVectorImpl::operator = (rhs); + return *this; +} + +template inline +const TYPE* SortedVector::array() const { + return static_cast(arrayImpl()); +} + +template inline +TYPE* SortedVector::editArray() { + return static_cast(editArrayImpl()); +} + + +template inline +const TYPE& SortedVector::operator[](size_t index) const { + LOG_FATAL_IF(index>=size(), + "%s: index=%u out of range (%u)", __PRETTY_FUNCTION__, + int(index), int(size())); + return *(array() + index); +} + +template inline +const TYPE& SortedVector::itemAt(size_t index) const { + return operator[](index); +} + +template inline +const TYPE& SortedVector::top() const { + return *(array() + size() - 1); +} + +template inline +ssize_t SortedVector::add(const TYPE& item) { + return SortedVectorImpl::add(&item); +} + +template inline +ssize_t SortedVector::indexOf(const TYPE& item) const { + return SortedVectorImpl::indexOf(&item); +} + +template inline +size_t SortedVector::orderOf(const TYPE& item) const { + return SortedVectorImpl::orderOf(&item); +} + +template inline +ssize_t SortedVector::merge(const Vector& vector) { + return SortedVectorImpl::merge(reinterpret_cast(vector)); +} + +template inline +ssize_t SortedVector::merge(const SortedVector& vector) { + return SortedVectorImpl::merge(reinterpret_cast(vector)); +} + +template inline +ssize_t SortedVector::remove(const TYPE& item) { + return SortedVectorImpl::remove(&item); +} + +template inline +ssize_t SortedVector::removeItemsAt(size_t index, size_t count) { + return VectorImpl::removeItemsAt(index, count); +} + +// --------------------------------------------------------------------------- + +template +void SortedVector::do_construct(void* storage, size_t num) const { + construct_type( reinterpret_cast(storage), num ); +} + +template +void SortedVector::do_destroy(void* storage, size_t num) const { + destroy_type( reinterpret_cast(storage), num ); +} + +template +void SortedVector::do_copy(void* dest, const void* from, size_t num) const { + copy_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +template +void SortedVector::do_splat(void* dest, const void* item, size_t num) const { + splat_type( reinterpret_cast(dest), reinterpret_cast(item), num ); +} + +template +void SortedVector::do_move_forward(void* dest, const void* from, size_t num) const { + move_forward_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +template +void SortedVector::do_move_backward(void* dest, const void* from, size_t num) const { + move_backward_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +template +int SortedVector::do_compare(const void* lhs, const void* rhs) const { + return compare_type( *reinterpret_cast(lhs), *reinterpret_cast(rhs) ); +} + +}; // namespace android + + +// --------------------------------------------------------------------------- + +#endif // ANDROID_SORTED_VECTOR_H diff --git a/third_party/android_system_core/include/utils/StopWatch.h b/third_party/android_system_core/include/utils/StopWatch.h new file mode 100644 index 00000000000000..693dd3ccfce40f --- /dev/null +++ b/third_party/android_system_core/include/utils/StopWatch.h @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_STOPWATCH_H +#define ANDROID_STOPWATCH_H + +#include +#include + +#include + +// --------------------------------------------------------------------------- + +namespace android { + +class StopWatch +{ +public: + StopWatch( const char *name, + int clock = SYSTEM_TIME_MONOTONIC, + uint32_t flags = 0); + ~StopWatch(); + + const char* name() const; + nsecs_t lap(); + nsecs_t elapsedTime() const; + + void reset(); + +private: + const char* mName; + int mClock; + uint32_t mFlags; + + struct lap_t { + nsecs_t soFar; + nsecs_t thisLap; + }; + + nsecs_t mStartTime; + lap_t mLaps[8]; + int mNumLaps; +}; + + +}; // namespace android + + +// --------------------------------------------------------------------------- + +#endif // ANDROID_STOPWATCH_H diff --git a/third_party/android_system_core/include/utils/String16.h b/third_party/android_system_core/include/utils/String16.h new file mode 100644 index 00000000000000..d131bfc6a72dff --- /dev/null +++ b/third_party/android_system_core/include/utils/String16.h @@ -0,0 +1,250 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_STRING16_H +#define ANDROID_STRING16_H + +#include +#include +#include +#include + +// --------------------------------------------------------------------------- + +extern "C" { + +} + +// --------------------------------------------------------------------------- + +namespace android { + +// --------------------------------------------------------------------------- + +class String8; +class TextOutput; + +//! This is a string holding UTF-16 characters. +class String16 +{ +public: + /* use String16(StaticLinkage) if you're statically linking against + * libutils and declaring an empty static String16, e.g.: + * + * static String16 sAStaticEmptyString(String16::kEmptyString); + * static String16 sAnotherStaticEmptyString(sAStaticEmptyString); + */ + enum StaticLinkage { kEmptyString }; + + String16(); + explicit String16(StaticLinkage); + String16(const String16& o); + String16(const String16& o, + size_t len, + size_t begin=0); + explicit String16(const char16_t* o); + explicit String16(const char16_t* o, size_t len); + explicit String16(const String8& o); + explicit String16(const char* o); + explicit String16(const char* o, size_t len); + + ~String16(); + + inline const char16_t* string() const; + inline size_t size() const; + + inline const SharedBuffer* sharedBuffer() const; + + void setTo(const String16& other); + status_t setTo(const char16_t* other); + status_t setTo(const char16_t* other, size_t len); + status_t setTo(const String16& other, + size_t len, + size_t begin=0); + + status_t append(const String16& other); + status_t append(const char16_t* other, size_t len); + + inline String16& operator=(const String16& other); + + inline String16& operator+=(const String16& other); + inline String16 operator+(const String16& other) const; + + status_t insert(size_t pos, const char16_t* chrs); + status_t insert(size_t pos, + const char16_t* chrs, size_t len); + + ssize_t findFirst(char16_t c) const; + ssize_t findLast(char16_t c) const; + + bool startsWith(const String16& prefix) const; + bool startsWith(const char16_t* prefix) const; + + status_t makeLower(); + + status_t replaceAll(char16_t replaceThis, + char16_t withThis); + + status_t remove(size_t len, size_t begin=0); + + inline int compare(const String16& other) const; + + inline bool operator<(const String16& other) const; + inline bool operator<=(const String16& other) const; + inline bool operator==(const String16& other) const; + inline bool operator!=(const String16& other) const; + inline bool operator>=(const String16& other) const; + inline bool operator>(const String16& other) const; + + inline bool operator<(const char16_t* other) const; + inline bool operator<=(const char16_t* other) const; + inline bool operator==(const char16_t* other) const; + inline bool operator!=(const char16_t* other) const; + inline bool operator>=(const char16_t* other) const; + inline bool operator>(const char16_t* other) const; + + inline operator const char16_t*() const; + +private: + const char16_t* mString; +}; + +// String16 can be trivially moved using memcpy() because moving does not +// require any change to the underlying SharedBuffer contents or reference count. +ANDROID_TRIVIAL_MOVE_TRAIT(String16) + +// --------------------------------------------------------------------------- +// No user servicable parts below. + +inline int compare_type(const String16& lhs, const String16& rhs) +{ + return lhs.compare(rhs); +} + +inline int strictly_order_type(const String16& lhs, const String16& rhs) +{ + return compare_type(lhs, rhs) < 0; +} + +inline const char16_t* String16::string() const +{ + return mString; +} + +inline size_t String16::size() const +{ + return SharedBuffer::sizeFromData(mString)/sizeof(char16_t)-1; +} + +inline const SharedBuffer* String16::sharedBuffer() const +{ + return SharedBuffer::bufferFromData(mString); +} + +inline String16& String16::operator=(const String16& other) +{ + setTo(other); + return *this; +} + +inline String16& String16::operator+=(const String16& other) +{ + append(other); + return *this; +} + +inline String16 String16::operator+(const String16& other) const +{ + String16 tmp(*this); + tmp += other; + return tmp; +} + +inline int String16::compare(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()); +} + +inline bool String16::operator<(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) < 0; +} + +inline bool String16::operator<=(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) <= 0; +} + +inline bool String16::operator==(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) == 0; +} + +inline bool String16::operator!=(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) != 0; +} + +inline bool String16::operator>=(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) >= 0; +} + +inline bool String16::operator>(const String16& other) const +{ + return strzcmp16(mString, size(), other.mString, other.size()) > 0; +} + +inline bool String16::operator<(const char16_t* other) const +{ + return strcmp16(mString, other) < 0; +} + +inline bool String16::operator<=(const char16_t* other) const +{ + return strcmp16(mString, other) <= 0; +} + +inline bool String16::operator==(const char16_t* other) const +{ + return strcmp16(mString, other) == 0; +} + +inline bool String16::operator!=(const char16_t* other) const +{ + return strcmp16(mString, other) != 0; +} + +inline bool String16::operator>=(const char16_t* other) const +{ + return strcmp16(mString, other) >= 0; +} + +inline bool String16::operator>(const char16_t* other) const +{ + return strcmp16(mString, other) > 0; +} + +inline String16::operator const char16_t*() const +{ + return mString; +} + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_STRING16_H diff --git a/third_party/android_system_core/include/utils/String8.h b/third_party/android_system_core/include/utils/String8.h new file mode 100644 index 00000000000000..ecfcf10be772b2 --- /dev/null +++ b/third_party/android_system_core/include/utils/String8.h @@ -0,0 +1,408 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_STRING8_H +#define ANDROID_STRING8_H + +#include +#include +#include +#include + +#include // for strcmp +#include + +// --------------------------------------------------------------------------- + +namespace android { + +class String16; +class TextOutput; + +//! This is a string holding UTF-8 characters. Does not allow the value more +// than 0x10FFFF, which is not valid unicode codepoint. +class String8 +{ +public: + /* use String8(StaticLinkage) if you're statically linking against + * libutils and declaring an empty static String8, e.g.: + * + * static String8 sAStaticEmptyString(String8::kEmptyString); + * static String8 sAnotherStaticEmptyString(sAStaticEmptyString); + */ + enum StaticLinkage { kEmptyString }; + + String8(); + explicit String8(StaticLinkage); + String8(const String8& o); + explicit String8(const char* o); + explicit String8(const char* o, size_t numChars); + + explicit String8(const String16& o); + explicit String8(const char16_t* o); + explicit String8(const char16_t* o, size_t numChars); + explicit String8(const char32_t* o); + explicit String8(const char32_t* o, size_t numChars); + ~String8(); + + static inline const String8 empty(); + + static String8 format(const char* fmt, ...) __attribute__((format (printf, 1, 2))); + static String8 formatV(const char* fmt, va_list args); + + inline const char* string() const; + inline size_t size() const; + inline size_t length() const; + inline size_t bytes() const; + inline bool isEmpty() const; + + inline const SharedBuffer* sharedBuffer() const; + + void clear(); + + void setTo(const String8& other); + status_t setTo(const char* other); + status_t setTo(const char* other, size_t numChars); + status_t setTo(const char16_t* other, size_t numChars); + status_t setTo(const char32_t* other, + size_t length); + + status_t append(const String8& other); + status_t append(const char* other); + status_t append(const char* other, size_t numChars); + + status_t appendFormat(const char* fmt, ...) + __attribute__((format (printf, 2, 3))); + status_t appendFormatV(const char* fmt, va_list args); + + // Note that this function takes O(N) time to calculate the value. + // No cache value is stored. + size_t getUtf32Length() const; + int32_t getUtf32At(size_t index, + size_t *next_index) const; + void getUtf32(char32_t* dst) const; + + inline String8& operator=(const String8& other); + inline String8& operator=(const char* other); + + inline String8& operator+=(const String8& other); + inline String8 operator+(const String8& other) const; + + inline String8& operator+=(const char* other); + inline String8 operator+(const char* other) const; + + inline int compare(const String8& other) const; + + inline bool operator<(const String8& other) const; + inline bool operator<=(const String8& other) const; + inline bool operator==(const String8& other) const; + inline bool operator!=(const String8& other) const; + inline bool operator>=(const String8& other) const; + inline bool operator>(const String8& other) const; + + inline bool operator<(const char* other) const; + inline bool operator<=(const char* other) const; + inline bool operator==(const char* other) const; + inline bool operator!=(const char* other) const; + inline bool operator>=(const char* other) const; + inline bool operator>(const char* other) const; + + inline operator const char*() const; + + char* lockBuffer(size_t size); + void unlockBuffer(); + status_t unlockBuffer(size_t size); + + // return the index of the first byte of other in this at or after + // start, or -1 if not found + ssize_t find(const char* other, size_t start = 0) const; + + // return true if this string contains the specified substring + inline bool contains(const char* other) const; + + // removes all occurrence of the specified substring + // returns true if any were found and removed + bool removeAll(const char* other); + + void toLower(); + void toLower(size_t start, size_t numChars); + void toUpper(); + void toUpper(size_t start, size_t numChars); + + + /* + * These methods operate on the string as if it were a path name. + */ + + /* + * Set the filename field to a specific value. + * + * Normalizes the filename, removing a trailing '/' if present. + */ + void setPathName(const char* name); + void setPathName(const char* name, size_t numChars); + + /* + * Get just the filename component. + * + * "/tmp/foo/bar.c" --> "bar.c" + */ + String8 getPathLeaf(void) const; + + /* + * Remove the last (file name) component, leaving just the directory + * name. + * + * "/tmp/foo/bar.c" --> "/tmp/foo" + * "/tmp" --> "" // ????? shouldn't this be "/" ???? XXX + * "bar.c" --> "" + */ + String8 getPathDir(void) const; + + /* + * Retrieve the front (root dir) component. Optionally also return the + * remaining components. + * + * "/tmp/foo/bar.c" --> "tmp" (remain = "foo/bar.c") + * "/tmp" --> "tmp" (remain = "") + * "bar.c" --> "bar.c" (remain = "") + */ + String8 walkPath(String8* outRemains = NULL) const; + + /* + * Return the filename extension. This is the last '.' and any number + * of characters that follow it. The '.' is included in case we + * decide to expand our definition of what constitutes an extension. + * + * "/tmp/foo/bar.c" --> ".c" + * "/tmp" --> "" + * "/tmp/foo.bar/baz" --> "" + * "foo.jpeg" --> ".jpeg" + * "foo." --> "" + */ + String8 getPathExtension(void) const; + + /* + * Return the path without the extension. Rules for what constitutes + * an extension are described in the comment for getPathExtension(). + * + * "/tmp/foo/bar.c" --> "/tmp/foo/bar" + */ + String8 getBasePath(void) const; + + /* + * Add a component to the pathname. We guarantee that there is + * exactly one path separator between the old path and the new. + * If there is no existing name, we just copy the new name in. + * + * If leaf is a fully qualified path (i.e. starts with '/', it + * replaces whatever was there before. + */ + String8& appendPath(const char* leaf); + String8& appendPath(const String8& leaf) { return appendPath(leaf.string()); } + + /* + * Like appendPath(), but does not affect this string. Returns a new one instead. + */ + String8 appendPathCopy(const char* leaf) const + { String8 p(*this); p.appendPath(leaf); return p; } + String8 appendPathCopy(const String8& leaf) const { return appendPathCopy(leaf.string()); } + + /* + * Converts all separators in this string to /, the default path separator. + * + * If the default OS separator is backslash, this converts all + * backslashes to slashes, in-place. Otherwise it does nothing. + * Returns self. + */ + String8& convertToResPath(); + +private: + status_t real_append(const char* other, size_t numChars); + char* find_extension(void) const; + + const char* mString; +}; + +// String8 can be trivially moved using memcpy() because moving does not +// require any change to the underlying SharedBuffer contents or reference count. +ANDROID_TRIVIAL_MOVE_TRAIT(String8) + +// --------------------------------------------------------------------------- +// No user servicable parts below. + +inline int compare_type(const String8& lhs, const String8& rhs) +{ + return lhs.compare(rhs); +} + +inline int strictly_order_type(const String8& lhs, const String8& rhs) +{ + return compare_type(lhs, rhs) < 0; +} + +inline const String8 String8::empty() { + return String8(); +} + +inline const char* String8::string() const +{ + return mString; +} + +inline size_t String8::length() const +{ + return SharedBuffer::sizeFromData(mString)-1; +} + +inline size_t String8::size() const +{ + return length(); +} + +inline bool String8::isEmpty() const +{ + return length() == 0; +} + +inline size_t String8::bytes() const +{ + return SharedBuffer::sizeFromData(mString)-1; +} + +inline const SharedBuffer* String8::sharedBuffer() const +{ + return SharedBuffer::bufferFromData(mString); +} + +inline bool String8::contains(const char* other) const +{ + return find(other) >= 0; +} + +inline String8& String8::operator=(const String8& other) +{ + setTo(other); + return *this; +} + +inline String8& String8::operator=(const char* other) +{ + setTo(other); + return *this; +} + +inline String8& String8::operator+=(const String8& other) +{ + append(other); + return *this; +} + +inline String8 String8::operator+(const String8& other) const +{ + String8 tmp(*this); + tmp += other; + return tmp; +} + +inline String8& String8::operator+=(const char* other) +{ + append(other); + return *this; +} + +inline String8 String8::operator+(const char* other) const +{ + String8 tmp(*this); + tmp += other; + return tmp; +} + +inline int String8::compare(const String8& other) const +{ + return strcmp(mString, other.mString); +} + +inline bool String8::operator<(const String8& other) const +{ + return strcmp(mString, other.mString) < 0; +} + +inline bool String8::operator<=(const String8& other) const +{ + return strcmp(mString, other.mString) <= 0; +} + +inline bool String8::operator==(const String8& other) const +{ + return strcmp(mString, other.mString) == 0; +} + +inline bool String8::operator!=(const String8& other) const +{ + return strcmp(mString, other.mString) != 0; +} + +inline bool String8::operator>=(const String8& other) const +{ + return strcmp(mString, other.mString) >= 0; +} + +inline bool String8::operator>(const String8& other) const +{ + return strcmp(mString, other.mString) > 0; +} + +inline bool String8::operator<(const char* other) const +{ + return strcmp(mString, other) < 0; +} + +inline bool String8::operator<=(const char* other) const +{ + return strcmp(mString, other) <= 0; +} + +inline bool String8::operator==(const char* other) const +{ + return strcmp(mString, other) == 0; +} + +inline bool String8::operator!=(const char* other) const +{ + return strcmp(mString, other) != 0; +} + +inline bool String8::operator>=(const char* other) const +{ + return strcmp(mString, other) >= 0; +} + +inline bool String8::operator>(const char* other) const +{ + return strcmp(mString, other) > 0; +} + +inline String8::operator const char*() const +{ + return mString; +} + +} // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_STRING8_H diff --git a/third_party/android_system_core/include/utils/StrongPointer.h b/third_party/android_system_core/include/utils/StrongPointer.h new file mode 100644 index 00000000000000..aba9577da4fc5d --- /dev/null +++ b/third_party/android_system_core/include/utils/StrongPointer.h @@ -0,0 +1,211 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_STRONG_POINTER_H +#define ANDROID_STRONG_POINTER_H + +#include + +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { + +template class wp; + +// --------------------------------------------------------------------------- + +#define COMPARE(_op_) \ +inline bool operator _op_ (const sp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} \ +inline bool operator _op_ (const T* o) const { \ + return m_ptr _op_ o; \ +} \ +template \ +inline bool operator _op_ (const sp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} \ +template \ +inline bool operator _op_ (const U* o) const { \ + return m_ptr _op_ o; \ +} \ +inline bool operator _op_ (const wp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} \ +template \ +inline bool operator _op_ (const wp& o) const { \ + return m_ptr _op_ o.m_ptr; \ +} + +// --------------------------------------------------------------------------- + +template +class sp { +public: + inline sp() : m_ptr(0) { } + + sp(T* other); + sp(const sp& other); + template sp(U* other); + template sp(const sp& other); + + ~sp(); + + // Assignment + + sp& operator = (T* other); + sp& operator = (const sp& other); + + template sp& operator = (const sp& other); + template sp& operator = (U* other); + + //! Special optimization for use by ProcessState (and nobody else). + void force_set(T* other); + + // Reset + + void clear(); + + // Accessors + + inline T& operator* () const { return *m_ptr; } + inline T* operator-> () const { return m_ptr; } + inline T* get() const { return m_ptr; } + + // Operators + + COMPARE(==) + COMPARE(!=) + COMPARE(>) + COMPARE(<) + COMPARE(<=) + COMPARE(>=) + +private: + template friend class sp; + template friend class wp; + void set_pointer(T* ptr); + T* m_ptr; +}; + +#undef COMPARE + +// --------------------------------------------------------------------------- +// No user serviceable parts below here. + +template +sp::sp(T* other) + : m_ptr(other) { + if (other) + other->incStrong(this); +} + +template +sp::sp(const sp& other) + : m_ptr(other.m_ptr) { + if (m_ptr) + m_ptr->incStrong(this); +} + +template template +sp::sp(U* other) + : m_ptr(other) { + if (other) + ((T*) other)->incStrong(this); +} + +template template +sp::sp(const sp& other) + : m_ptr(other.m_ptr) { + if (m_ptr) + m_ptr->incStrong(this); +} + +template +sp::~sp() { + if (m_ptr) + m_ptr->decStrong(this); +} + +template +sp& sp::operator =(const sp& other) { + T* otherPtr(other.m_ptr); + if (otherPtr) + otherPtr->incStrong(this); + if (m_ptr) + m_ptr->decStrong(this); + m_ptr = otherPtr; + return *this; +} + +template +sp& sp::operator =(T* other) { + if (other) + other->incStrong(this); + if (m_ptr) + m_ptr->decStrong(this); + m_ptr = other; + return *this; +} + +template template +sp& sp::operator =(const sp& other) { + T* otherPtr(other.m_ptr); + if (otherPtr) + otherPtr->incStrong(this); + if (m_ptr) + m_ptr->decStrong(this); + m_ptr = otherPtr; + return *this; +} + +template template +sp& sp::operator =(U* other) { + if (other) + ((T*) other)->incStrong(this); + if (m_ptr) + m_ptr->decStrong(this); + m_ptr = other; + return *this; +} + +template +void sp::force_set(T* other) { + other->forceIncStrong(this); + m_ptr = other; +} + +template +void sp::clear() { + if (m_ptr) { + m_ptr->decStrong(this); + m_ptr = 0; + } +} + +template +void sp::set_pointer(T* ptr) { + m_ptr = ptr; +} + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_STRONG_POINTER_H diff --git a/third_party/android_system_core/include/utils/SystemClock.h b/third_party/android_system_core/include/utils/SystemClock.h new file mode 100644 index 00000000000000..01db340780032b --- /dev/null +++ b/third_party/android_system_core/include/utils/SystemClock.h @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UTILS_SYSTEMCLOCK_H +#define ANDROID_UTILS_SYSTEMCLOCK_H + +#include +#include + +namespace android { + +int64_t uptimeMillis(); +int64_t elapsedRealtime(); +int64_t elapsedRealtimeNano(); + +}; // namespace android + +#endif // ANDROID_UTILS_SYSTEMCLOCK_H + diff --git a/third_party/android_system_core/include/utils/Thread.h b/third_party/android_system_core/include/utils/Thread.h new file mode 100644 index 00000000000000..28839fdedc1c06 --- /dev/null +++ b/third_party/android_system_core/include/utils/Thread.h @@ -0,0 +1,116 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_THREAD_H +#define _LIBS_UTILS_THREAD_H + +#include +#include +#include + +#if !defined(_WIN32) +# include +#endif + +#include +#include +#include +#include +#include +#include + +// --------------------------------------------------------------------------- +namespace android { +// --------------------------------------------------------------------------- + +class Thread : virtual public RefBase +{ +public: + // Create a Thread object, but doesn't create or start the associated + // thread. See the run() method. + Thread(bool canCallJava = true); + virtual ~Thread(); + + // Start the thread in threadLoop() which needs to be implemented. + virtual status_t run( const char* name = 0, + int32_t priority = PRIORITY_DEFAULT, + size_t stack = 0); + + // Ask this object's thread to exit. This function is asynchronous, when the + // function returns the thread might still be running. Of course, this + // function can be called from a different thread. + virtual void requestExit(); + + // Good place to do one-time initializations + virtual status_t readyToRun(); + + // Call requestExit() and wait until this object's thread exits. + // BE VERY CAREFUL of deadlocks. In particular, it would be silly to call + // this function from this object's thread. Will return WOULD_BLOCK in + // that case. + status_t requestExitAndWait(); + + // Wait until this object's thread exits. Returns immediately if not yet running. + // Do not call from this object's thread; will return WOULD_BLOCK in that case. + status_t join(); + + // Indicates whether this thread is running or not. + bool isRunning() const; + +#ifdef HAVE_ANDROID_OS + // Return the thread's kernel ID, same as the thread itself calling gettid(), + // or -1 if the thread is not running. + pid_t getTid() const; +#endif + +protected: + // exitPending() returns true if requestExit() has been called. + bool exitPending() const; + +private: + // Derived class must implement threadLoop(). The thread starts its life + // here. There are two ways of using the Thread object: + // 1) loop: if threadLoop() returns true, it will be called again if + // requestExit() wasn't called. + // 2) once: if threadLoop() returns false, the thread will exit upon return. + virtual bool threadLoop() = 0; + +private: + Thread& operator=(const Thread&); + static int _threadLoop(void* user); + const bool mCanCallJava; + // always hold mLock when reading or writing + thread_id_t mThread; + mutable Mutex mLock; + Condition mThreadExitedCondition; + status_t mStatus; + // note that all accesses of mExitPending and mRunning need to hold mLock + volatile bool mExitPending; + volatile bool mRunning; + sp mHoldSelf; +#ifdef HAVE_ANDROID_OS + // legacy for debugging, not used by getTid() as it is set by the child thread + // and so is not initialized until the child reaches that point + pid_t mTid; +#endif +}; + + +}; // namespace android + +// --------------------------------------------------------------------------- +#endif // _LIBS_UTILS_THREAD_H +// --------------------------------------------------------------------------- diff --git a/third_party/android_system_core/include/utils/ThreadDefs.h b/third_party/android_system_core/include/utils/ThreadDefs.h new file mode 100644 index 00000000000000..9711c137925e96 --- /dev/null +++ b/third_party/android_system_core/include/utils/ThreadDefs.h @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_THREAD_DEFS_H +#define _LIBS_UTILS_THREAD_DEFS_H + +#include +#include +#include +#include + +// --------------------------------------------------------------------------- +// C API + +#ifdef __cplusplus +extern "C" { +#endif + +typedef void* android_thread_id_t; + +typedef int (*android_thread_func_t)(void*); + +#ifdef __cplusplus +} // extern "C" +#endif + +// --------------------------------------------------------------------------- +// C++ API +#ifdef __cplusplus +namespace android { +// --------------------------------------------------------------------------- + +typedef android_thread_id_t thread_id_t; +typedef android_thread_func_t thread_func_t; + +enum { + PRIORITY_LOWEST = ANDROID_PRIORITY_LOWEST, + PRIORITY_BACKGROUND = ANDROID_PRIORITY_BACKGROUND, + PRIORITY_NORMAL = ANDROID_PRIORITY_NORMAL, + PRIORITY_FOREGROUND = ANDROID_PRIORITY_FOREGROUND, + PRIORITY_DISPLAY = ANDROID_PRIORITY_DISPLAY, + PRIORITY_URGENT_DISPLAY = ANDROID_PRIORITY_URGENT_DISPLAY, + PRIORITY_AUDIO = ANDROID_PRIORITY_AUDIO, + PRIORITY_URGENT_AUDIO = ANDROID_PRIORITY_URGENT_AUDIO, + PRIORITY_HIGHEST = ANDROID_PRIORITY_HIGHEST, + PRIORITY_DEFAULT = ANDROID_PRIORITY_DEFAULT, + PRIORITY_MORE_FAVORABLE = ANDROID_PRIORITY_MORE_FAVORABLE, + PRIORITY_LESS_FAVORABLE = ANDROID_PRIORITY_LESS_FAVORABLE, +}; + +// --------------------------------------------------------------------------- +}; // namespace android +#endif // __cplusplus +// --------------------------------------------------------------------------- + + +#endif // _LIBS_UTILS_THREAD_DEFS_H diff --git a/third_party/android_system_core/include/utils/Timers.h b/third_party/android_system_core/include/utils/Timers.h new file mode 100644 index 00000000000000..54ec47489fcb3c --- /dev/null +++ b/third_party/android_system_core/include/utils/Timers.h @@ -0,0 +1,108 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// Timer functions. +// +#ifndef _LIBS_UTILS_TIMERS_H +#define _LIBS_UTILS_TIMERS_H + +#include +#include +#include + +#include + +// ------------------------------------------------------------------ +// C API + +#ifdef __cplusplus +extern "C" { +#endif + +typedef int64_t nsecs_t; // nano-seconds + +static CONSTEXPR inline nsecs_t seconds_to_nanoseconds(nsecs_t secs) +{ + return secs*1000000000; +} + +static CONSTEXPR inline nsecs_t milliseconds_to_nanoseconds(nsecs_t secs) +{ + return secs*1000000; +} + +static CONSTEXPR inline nsecs_t microseconds_to_nanoseconds(nsecs_t secs) +{ + return secs*1000; +} + +static CONSTEXPR inline nsecs_t nanoseconds_to_seconds(nsecs_t secs) +{ + return secs/1000000000; +} + +static CONSTEXPR inline nsecs_t nanoseconds_to_milliseconds(nsecs_t secs) +{ + return secs/1000000; +} + +static CONSTEXPR inline nsecs_t nanoseconds_to_microseconds(nsecs_t secs) +{ + return secs/1000; +} + +static CONSTEXPR inline nsecs_t s2ns(nsecs_t v) {return seconds_to_nanoseconds(v);} +static CONSTEXPR inline nsecs_t ms2ns(nsecs_t v) {return milliseconds_to_nanoseconds(v);} +static CONSTEXPR inline nsecs_t us2ns(nsecs_t v) {return microseconds_to_nanoseconds(v);} +static CONSTEXPR inline nsecs_t ns2s(nsecs_t v) {return nanoseconds_to_seconds(v);} +static CONSTEXPR inline nsecs_t ns2ms(nsecs_t v) {return nanoseconds_to_milliseconds(v);} +static CONSTEXPR inline nsecs_t ns2us(nsecs_t v) {return nanoseconds_to_microseconds(v);} + +static CONSTEXPR inline nsecs_t seconds(nsecs_t v) { return s2ns(v); } +static CONSTEXPR inline nsecs_t milliseconds(nsecs_t v) { return ms2ns(v); } +static CONSTEXPR inline nsecs_t microseconds(nsecs_t v) { return us2ns(v); } + +enum { + SYSTEM_TIME_REALTIME = 0, // system-wide realtime clock + SYSTEM_TIME_MONOTONIC = 1, // monotonic time since unspecified starting point + SYSTEM_TIME_PROCESS = 2, // high-resolution per-process clock + SYSTEM_TIME_THREAD = 3, // high-resolution per-thread clock + SYSTEM_TIME_BOOTTIME = 4 // same as SYSTEM_TIME_MONOTONIC, but including CPU suspend time +}; + +// return the system-time according to the specified clock +#ifdef __cplusplus +nsecs_t systemTime(int clock = SYSTEM_TIME_MONOTONIC); +#else +nsecs_t systemTime(int clock); +#endif // def __cplusplus + +/** + * Returns the number of milliseconds to wait between the reference time and the timeout time. + * If the timeout is in the past relative to the reference time, returns 0. + * If the timeout is more than INT_MAX milliseconds in the future relative to the reference time, + * such as when timeoutTime == LLONG_MAX, returns -1 to indicate an infinite timeout delay. + * Otherwise, returns the difference between the reference time and timeout time + * rounded up to the next millisecond. + */ +int toMillisecondTimeoutDelay(nsecs_t referenceTime, nsecs_t timeoutTime); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif // _LIBS_UTILS_TIMERS_H diff --git a/third_party/android_system_core/include/utils/Tokenizer.h b/third_party/android_system_core/include/utils/Tokenizer.h new file mode 100644 index 00000000000000..bb25f374cb343c --- /dev/null +++ b/third_party/android_system_core/include/utils/Tokenizer.h @@ -0,0 +1,136 @@ +/* + * Copyright (C) 2010 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _UTILS_TOKENIZER_H +#define _UTILS_TOKENIZER_H + +#include +#include +#include +#include + +namespace android { + +/** + * A simple tokenizer for loading and parsing ASCII text files line by line. + */ +class Tokenizer { + Tokenizer(const String8& filename, FileMap* fileMap, char* buffer, + bool ownBuffer, size_t length); + +public: + ~Tokenizer(); + + /** + * Opens a file and maps it into memory. + * + * Returns NO_ERROR and a tokenizer for the file, if successful. + * Otherwise returns an error and sets outTokenizer to NULL. + */ + static status_t open(const String8& filename, Tokenizer** outTokenizer); + + /** + * Prepares to tokenize the contents of a string. + * + * Returns NO_ERROR and a tokenizer for the string, if successful. + * Otherwise returns an error and sets outTokenizer to NULL. + */ + static status_t fromContents(const String8& filename, + const char* contents, Tokenizer** outTokenizer); + + /** + * Returns true if at the end of the file. + */ + inline bool isEof() const { return mCurrent == getEnd(); } + + /** + * Returns true if at the end of the line or end of the file. + */ + inline bool isEol() const { return isEof() || *mCurrent == '\n'; } + + /** + * Gets the name of the file. + */ + inline String8 getFilename() const { return mFilename; } + + /** + * Gets a 1-based line number index for the current position. + */ + inline int32_t getLineNumber() const { return mLineNumber; } + + /** + * Formats a location string consisting of the filename and current line number. + * Returns a string like "MyFile.txt:33". + */ + String8 getLocation() const; + + /** + * Gets the character at the current position. + * Returns null at end of file. + */ + inline char peekChar() const { return isEof() ? '\0' : *mCurrent; } + + /** + * Gets the remainder of the current line as a string, excluding the newline character. + */ + String8 peekRemainderOfLine() const; + + /** + * Gets the character at the current position and advances past it. + * Returns null at end of file. + */ + inline char nextChar() { return isEof() ? '\0' : *(mCurrent++); } + + /** + * Gets the next token on this line stopping at the specified delimiters + * or the end of the line whichever comes first and advances past it. + * Also stops at embedded nulls. + * Returns the token or an empty string if the current character is a delimiter + * or is at the end of the line. + */ + String8 nextToken(const char* delimiters); + + /** + * Advances to the next line. + * Does nothing if already at the end of the file. + */ + void nextLine(); + + /** + * Skips over the specified delimiters in the line. + * Also skips embedded nulls. + */ + void skipDelimiters(const char* delimiters); + +private: + Tokenizer(const Tokenizer& other); // not copyable + + String8 mFilename; + FileMap* mFileMap; + char* mBuffer; + bool mOwnBuffer; + size_t mLength; + + const char* mCurrent; + int32_t mLineNumber; + + inline const char* getEnd() const { return mBuffer + mLength; } + +}; + +} // namespace android + +#endif // _UTILS_TOKENIZER_H diff --git a/third_party/android_system_core/include/utils/Trace.h b/third_party/android_system_core/include/utils/Trace.h new file mode 100644 index 00000000000000..6ee343d79ad039 --- /dev/null +++ b/third_party/android_system_core/include/utils/Trace.h @@ -0,0 +1,69 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_TRACE_H +#define ANDROID_TRACE_H + +#ifdef HAVE_ANDROID_OS + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +// See for more ATRACE_* macros. + +// ATRACE_NAME traces the beginning and end of the current scope. To trace +// the correct start and end times this macro should be declared first in the +// scope body. +#define ATRACE_NAME(name) android::ScopedTrace ___tracer(ATRACE_TAG, name) +// ATRACE_CALL is an ATRACE_NAME that uses the current function name. +#define ATRACE_CALL() ATRACE_NAME(__FUNCTION__) + +namespace android { + +class ScopedTrace { +public: +inline ScopedTrace(uint64_t tag, const char* name) + : mTag(tag) { + atrace_begin(mTag,name); +} + +inline ~ScopedTrace() { + atrace_end(mTag); +} + +private: + uint64_t mTag; +}; + +}; // namespace android + +#else // HAVE_ANDROID_OS + +#define ATRACE_NAME(...) +#define ATRACE_CALL() + +#endif // HAVE_ANDROID_OS + +#endif // ANDROID_TRACE_H diff --git a/third_party/android_system_core/include/utils/TypeHelpers.h b/third_party/android_system_core/include/utils/TypeHelpers.h new file mode 100644 index 00000000000000..13c90815994736 --- /dev/null +++ b/third_party/android_system_core/include/utils/TypeHelpers.h @@ -0,0 +1,302 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_TYPE_HELPERS_H +#define ANDROID_TYPE_HELPERS_H + +#include +#include +#include +#include + +// --------------------------------------------------------------------------- + +namespace android { + +/* + * Types traits + */ + +template struct trait_trivial_ctor { enum { value = false }; }; +template struct trait_trivial_dtor { enum { value = false }; }; +template struct trait_trivial_copy { enum { value = false }; }; +template struct trait_trivial_move { enum { value = false }; }; +template struct trait_pointer { enum { value = false }; }; +template struct trait_pointer { enum { value = true }; }; + +template +struct traits { + enum { + // whether this type is a pointer + is_pointer = trait_pointer::value, + // whether this type's constructor is a no-op + has_trivial_ctor = is_pointer || trait_trivial_ctor::value, + // whether this type's destructor is a no-op + has_trivial_dtor = is_pointer || trait_trivial_dtor::value, + // whether this type type can be copy-constructed with memcpy + has_trivial_copy = is_pointer || trait_trivial_copy::value, + // whether this type can be moved with memmove + has_trivial_move = is_pointer || trait_trivial_move::value + }; +}; + +template +struct aggregate_traits { + enum { + is_pointer = false, + has_trivial_ctor = + traits::has_trivial_ctor && traits::has_trivial_ctor, + has_trivial_dtor = + traits::has_trivial_dtor && traits::has_trivial_dtor, + has_trivial_copy = + traits::has_trivial_copy && traits::has_trivial_copy, + has_trivial_move = + traits::has_trivial_move && traits::has_trivial_move + }; +}; + +#define ANDROID_TRIVIAL_CTOR_TRAIT( T ) \ + template<> struct trait_trivial_ctor< T > { enum { value = true }; }; + +#define ANDROID_TRIVIAL_DTOR_TRAIT( T ) \ + template<> struct trait_trivial_dtor< T > { enum { value = true }; }; + +#define ANDROID_TRIVIAL_COPY_TRAIT( T ) \ + template<> struct trait_trivial_copy< T > { enum { value = true }; }; + +#define ANDROID_TRIVIAL_MOVE_TRAIT( T ) \ + template<> struct trait_trivial_move< T > { enum { value = true }; }; + +#define ANDROID_BASIC_TYPES_TRAITS( T ) \ + ANDROID_TRIVIAL_CTOR_TRAIT( T ) \ + ANDROID_TRIVIAL_DTOR_TRAIT( T ) \ + ANDROID_TRIVIAL_COPY_TRAIT( T ) \ + ANDROID_TRIVIAL_MOVE_TRAIT( T ) + +// --------------------------------------------------------------------------- + +/* + * basic types traits + */ + +ANDROID_BASIC_TYPES_TRAITS( void ) +ANDROID_BASIC_TYPES_TRAITS( bool ) +ANDROID_BASIC_TYPES_TRAITS( char ) +ANDROID_BASIC_TYPES_TRAITS( unsigned char ) +ANDROID_BASIC_TYPES_TRAITS( short ) +ANDROID_BASIC_TYPES_TRAITS( unsigned short ) +ANDROID_BASIC_TYPES_TRAITS( int ) +ANDROID_BASIC_TYPES_TRAITS( unsigned int ) +ANDROID_BASIC_TYPES_TRAITS( long ) +ANDROID_BASIC_TYPES_TRAITS( unsigned long ) +ANDROID_BASIC_TYPES_TRAITS( long long ) +ANDROID_BASIC_TYPES_TRAITS( unsigned long long ) +ANDROID_BASIC_TYPES_TRAITS( float ) +ANDROID_BASIC_TYPES_TRAITS( double ) + +// --------------------------------------------------------------------------- + + +/* + * compare and order types + */ + +template inline +int strictly_order_type(const TYPE& lhs, const TYPE& rhs) { + return (lhs < rhs) ? 1 : 0; +} + +template inline +int compare_type(const TYPE& lhs, const TYPE& rhs) { + return strictly_order_type(rhs, lhs) - strictly_order_type(lhs, rhs); +} + +/* + * create, destroy, copy and move types... + */ + +template inline +void construct_type(TYPE* p, size_t n) { + if (!traits::has_trivial_ctor) { + while (n--) { + new(p++) TYPE; + } + } +} + +template inline +void destroy_type(TYPE* p, size_t n) { + if (!traits::has_trivial_dtor) { + while (n--) { + p->~TYPE(); + p++; + } + } +} + +template inline +void copy_type(TYPE* d, const TYPE* s, size_t n) { + if (!traits::has_trivial_copy) { + while (n--) { + new(d) TYPE(*s); + d++, s++; + } + } else { + memcpy(d,s,n*sizeof(TYPE)); + } +} + +template inline +void splat_type(TYPE* where, const TYPE* what, size_t n) { + if (!traits::has_trivial_copy) { + while (n--) { + new(where) TYPE(*what); + where++; + } + } else { + while (n--) { + *where++ = *what; + } + } +} + +template inline +void move_forward_type(TYPE* d, const TYPE* s, size_t n = 1) { + if ((traits::has_trivial_dtor && traits::has_trivial_copy) + || traits::has_trivial_move) + { + memmove(d,s,n*sizeof(TYPE)); + } else { + d += n; + s += n; + while (n--) { + --d, --s; + if (!traits::has_trivial_copy) { + new(d) TYPE(*s); + } else { + *d = *s; + } + if (!traits::has_trivial_dtor) { + s->~TYPE(); + } + } + } +} + +template inline +void move_backward_type(TYPE* d, const TYPE* s, size_t n = 1) { + if ((traits::has_trivial_dtor && traits::has_trivial_copy) + || traits::has_trivial_move) + { + memmove(d,s,n*sizeof(TYPE)); + } else { + while (n--) { + if (!traits::has_trivial_copy) { + new(d) TYPE(*s); + } else { + *d = *s; + } + if (!traits::has_trivial_dtor) { + s->~TYPE(); + } + d++, s++; + } + } +} + +// --------------------------------------------------------------------------- + +/* + * a key/value pair + */ + +template +struct key_value_pair_t { + typedef KEY key_t; + typedef VALUE value_t; + + KEY key; + VALUE value; + key_value_pair_t() { } + key_value_pair_t(const key_value_pair_t& o) : key(o.key), value(o.value) { } + key_value_pair_t(const KEY& k, const VALUE& v) : key(k), value(v) { } + key_value_pair_t(const KEY& k) : key(k) { } + inline bool operator < (const key_value_pair_t& o) const { + return strictly_order_type(key, o.key); + } + inline const KEY& getKey() const { + return key; + } + inline const VALUE& getValue() const { + return value; + } +}; + +template +struct trait_trivial_ctor< key_value_pair_t > +{ enum { value = aggregate_traits::has_trivial_ctor }; }; +template +struct trait_trivial_dtor< key_value_pair_t > +{ enum { value = aggregate_traits::has_trivial_dtor }; }; +template +struct trait_trivial_copy< key_value_pair_t > +{ enum { value = aggregate_traits::has_trivial_copy }; }; +template +struct trait_trivial_move< key_value_pair_t > +{ enum { value = aggregate_traits::has_trivial_move }; }; + +// --------------------------------------------------------------------------- + +/* + * Hash codes. + */ +typedef uint32_t hash_t; + +template +hash_t hash_type(const TKey& key); + +/* Built-in hash code specializations. + * Assumes pointers are 32bit. */ +#define ANDROID_INT32_HASH(T) \ + template <> inline hash_t hash_type(const T& value) { return hash_t(value); } +#define ANDROID_INT64_HASH(T) \ + template <> inline hash_t hash_type(const T& value) { \ + return hash_t((value >> 32) ^ value); } +#define ANDROID_REINTERPRET_HASH(T, R) \ + template <> inline hash_t hash_type(const T& value) { \ + return hash_type(*reinterpret_cast(&value)); } + +ANDROID_INT32_HASH(bool) +ANDROID_INT32_HASH(int8_t) +ANDROID_INT32_HASH(uint8_t) +ANDROID_INT32_HASH(int16_t) +ANDROID_INT32_HASH(uint16_t) +ANDROID_INT32_HASH(int32_t) +ANDROID_INT32_HASH(uint32_t) +ANDROID_INT64_HASH(int64_t) +ANDROID_INT64_HASH(uint64_t) +ANDROID_REINTERPRET_HASH(float, uint32_t) +ANDROID_REINTERPRET_HASH(double, uint64_t) + +template inline hash_t hash_type(T* const & value) { + return hash_type(uintptr_t(value)); +} + +}; // namespace android + +// --------------------------------------------------------------------------- + +#endif // ANDROID_TYPE_HELPERS_H diff --git a/third_party/android_system_core/include/utils/Unicode.h b/third_party/android_system_core/include/utils/Unicode.h new file mode 100644 index 00000000000000..4e17cc3d9c5a46 --- /dev/null +++ b/third_party/android_system_core/include/utils/Unicode.h @@ -0,0 +1,172 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_UNICODE_H +#define ANDROID_UNICODE_H + +#include +#include + +extern "C" { + +// Standard string functions on char16_t strings. +int strcmp16(const char16_t *, const char16_t *); +int strncmp16(const char16_t *s1, const char16_t *s2, size_t n); +size_t strlen16(const char16_t *); +size_t strnlen16(const char16_t *, size_t); +char16_t *strcpy16(char16_t *, const char16_t *); +char16_t *strncpy16(char16_t *, const char16_t *, size_t); + +// Version of comparison that supports embedded nulls. +// This is different than strncmp() because we don't stop +// at a nul character and consider the strings to be different +// if the lengths are different (thus we need to supply the +// lengths of both strings). This can also be used when +// your string is not nul-terminated as it will have the +// equivalent result as strcmp16 (unlike strncmp16). +int strzcmp16(const char16_t *s1, size_t n1, const char16_t *s2, size_t n2); + +// Version of strzcmp16 for comparing strings in different endianness. +int strzcmp16_h_n(const char16_t *s1H, size_t n1, const char16_t *s2N, size_t n2); + +// Standard string functions on char32_t strings. +size_t strlen32(const char32_t *); +size_t strnlen32(const char32_t *, size_t); + +/** + * Measure the length of a UTF-32 string in UTF-8. If the string is invalid + * such as containing a surrogate character, -1 will be returned. + */ +ssize_t utf32_to_utf8_length(const char32_t *src, size_t src_len); + +/** + * Stores a UTF-8 string converted from "src" in "dst", if "dst_length" is not + * large enough to store the string, the part of the "src" string is stored + * into "dst" as much as possible. See the examples for more detail. + * Returns the size actually used for storing the string. + * dst" is not null-terminated when dst_len is fully used (like strncpy). + * + * Example 1 + * "src" == \u3042\u3044 (\xE3\x81\x82\xE3\x81\x84) + * "src_len" == 2 + * "dst_len" >= 7 + * -> + * Returned value == 6 + * "dst" becomes \xE3\x81\x82\xE3\x81\x84\0 + * (note that "dst" is null-terminated) + * + * Example 2 + * "src" == \u3042\u3044 (\xE3\x81\x82\xE3\x81\x84) + * "src_len" == 2 + * "dst_len" == 5 + * -> + * Returned value == 3 + * "dst" becomes \xE3\x81\x82\0 + * (note that "dst" is null-terminated, but \u3044 is not stored in "dst" + * since "dst" does not have enough size to store the character) + * + * Example 3 + * "src" == \u3042\u3044 (\xE3\x81\x82\xE3\x81\x84) + * "src_len" == 2 + * "dst_len" == 6 + * -> + * Returned value == 6 + * "dst" becomes \xE3\x81\x82\xE3\x81\x84 + * (note that "dst" is NOT null-terminated, like strncpy) + */ +void utf32_to_utf8(const char32_t* src, size_t src_len, char* dst, size_t dst_len); + +/** + * Returns the unicode value at "index". + * Returns -1 when the index is invalid (equals to or more than "src_len"). + * If returned value is positive, it is able to be converted to char32_t, which + * is unsigned. Then, if "next_index" is not NULL, the next index to be used is + * stored in "next_index". "next_index" can be NULL. + */ +int32_t utf32_from_utf8_at(const char *src, size_t src_len, size_t index, size_t *next_index); + + +/** + * Returns the UTF-8 length of UTF-16 string "src". + */ +ssize_t utf16_to_utf8_length(const char16_t *src, size_t src_len); + +/** + * Converts a UTF-16 string to UTF-8. The destination buffer must be large + * enough to fit the UTF-16 as measured by utf16_to_utf8_length with an added + * NULL terminator. + */ +void utf16_to_utf8(const char16_t* src, size_t src_len, char* dst, size_t dst_len); + +/** + * Returns the length of "src" when "src" is valid UTF-8 string. + * Returns 0 if src is NULL or 0-length string. Returns -1 when the source + * is an invalid string. + * + * This function should be used to determine whether "src" is valid UTF-8 + * characters with valid unicode codepoints. "src" must be null-terminated. + * + * If you are going to use other utf8_to_... functions defined in this header + * with string which may not be valid UTF-8 with valid codepoint (form 0 to + * 0x10FFFF), you should use this function before calling others, since the + * other functions do not check whether the string is valid UTF-8 or not. + * + * If you do not care whether "src" is valid UTF-8 or not, you should use + * strlen() as usual, which should be much faster. + */ +ssize_t utf8_length(const char *src); + +/** + * Measure the length of a UTF-32 string. + */ +size_t utf8_to_utf32_length(const char *src, size_t src_len); + +/** + * Stores a UTF-32 string converted from "src" in "dst". "dst" must be large + * enough to store the entire converted string as measured by + * utf8_to_utf32_length plus space for a NULL terminator. + */ +void utf8_to_utf32(const char* src, size_t src_len, char32_t* dst); + +/** + * Returns the UTF-16 length of UTF-8 string "src". + */ +ssize_t utf8_to_utf16_length(const uint8_t* src, size_t srcLen); + +/** + * Convert UTF-8 to UTF-16 including surrogate pairs. + * Returns a pointer to the end of the string (where a null terminator might go + * if you wanted to add one). + */ +char16_t* utf8_to_utf16_no_null_terminator(const uint8_t* src, size_t srcLen, char16_t* dst); + +/** + * Convert UTF-8 to UTF-16 including surrogate pairs. The destination buffer + * must be large enough to hold the result as measured by utf8_to_utf16_length + * plus an added NULL terminator. + */ +void utf8_to_utf16(const uint8_t* src, size_t srcLen, char16_t* dst); + +/** + * Like utf8_to_utf16_no_null_terminator, but you can supply a maximum length of the + * decoded string. The decoded string will fill up to that length; if it is longer + * the returned pointer will be to the character after dstLen. + */ +char16_t* utf8_to_utf16_n(const uint8_t* src, size_t srcLen, char16_t* dst, size_t dstLen); + +} + +#endif diff --git a/third_party/android_system_core/include/utils/Vector.h b/third_party/android_system_core/include/utils/Vector.h new file mode 100644 index 00000000000000..ed7b725213150a --- /dev/null +++ b/third_party/android_system_core/include/utils/Vector.h @@ -0,0 +1,423 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_VECTOR_H +#define ANDROID_VECTOR_H + +#include +#include +#include + +#include + +#include +#include + +// --------------------------------------------------------------------------- + +namespace android { + +template +class SortedVector; + +/*! + * The main templated vector class ensuring type safety + * while making use of VectorImpl. + * This is the class users want to use. + */ + +template +class Vector : private VectorImpl +{ +public: + typedef TYPE value_type; + + /*! + * Constructors and destructors + */ + + Vector(); + Vector(const Vector& rhs); + explicit Vector(const SortedVector& rhs); + virtual ~Vector(); + + /*! copy operator */ + const Vector& operator = (const Vector& rhs) const; + Vector& operator = (const Vector& rhs); + + const Vector& operator = (const SortedVector& rhs) const; + Vector& operator = (const SortedVector& rhs); + + /* + * empty the vector + */ + + inline void clear() { VectorImpl::clear(); } + + /*! + * vector stats + */ + + //! returns number of items in the vector + inline size_t size() const { return VectorImpl::size(); } + //! returns whether or not the vector is empty + inline bool isEmpty() const { return VectorImpl::isEmpty(); } + //! returns how many items can be stored without reallocating the backing store + inline size_t capacity() const { return VectorImpl::capacity(); } + //! sets the capacity. capacity can never be reduced less than size() + inline ssize_t setCapacity(size_t size) { return VectorImpl::setCapacity(size); } + + /*! + * set the size of the vector. items are appended with the default + * constructor, or removed from the end as needed. + */ + inline ssize_t resize(size_t size) { return VectorImpl::resize(size); } + + /*! + * C-style array access + */ + + //! read-only C-style access + inline const TYPE* array() const; + //! read-write C-style access + TYPE* editArray(); + + /*! + * accessors + */ + + //! read-only access to an item at a given index + inline const TYPE& operator [] (size_t index) const; + //! alternate name for operator [] + inline const TYPE& itemAt(size_t index) const; + //! stack-usage of the vector. returns the top of the stack (last element) + const TYPE& top() const; + + /*! + * modifying the array + */ + + //! copy-on write support, grants write access to an item + TYPE& editItemAt(size_t index); + //! grants right access to the top of the stack (last element) + TYPE& editTop(); + + /*! + * append/insert another vector + */ + + //! insert another vector at a given index + ssize_t insertVectorAt(const Vector& vector, size_t index); + + //! append another vector at the end of this one + ssize_t appendVector(const Vector& vector); + + + //! insert an array at a given index + ssize_t insertArrayAt(const TYPE* array, size_t index, size_t length); + + //! append an array at the end of this vector + ssize_t appendArray(const TYPE* array, size_t length); + + /*! + * add/insert/replace items + */ + + //! insert one or several items initialized with their default constructor + inline ssize_t insertAt(size_t index, size_t numItems = 1); + //! insert one or several items initialized from a prototype item + ssize_t insertAt(const TYPE& prototype_item, size_t index, size_t numItems = 1); + //! pop the top of the stack (removes the last element). No-op if the stack's empty + inline void pop(); + //! pushes an item initialized with its default constructor + inline void push(); + //! pushes an item on the top of the stack + void push(const TYPE& item); + //! same as push() but returns the index the item was added at (or an error) + inline ssize_t add(); + //! same as push() but returns the index the item was added at (or an error) + ssize_t add(const TYPE& item); + //! replace an item with a new one initialized with its default constructor + inline ssize_t replaceAt(size_t index); + //! replace an item with a new one + ssize_t replaceAt(const TYPE& item, size_t index); + + /*! + * remove items + */ + + //! remove several items + inline ssize_t removeItemsAt(size_t index, size_t count = 1); + //! remove one item + inline ssize_t removeAt(size_t index) { return removeItemsAt(index); } + + /*! + * sort (stable) the array + */ + + typedef int (*compar_t)(const TYPE* lhs, const TYPE* rhs); + typedef int (*compar_r_t)(const TYPE* lhs, const TYPE* rhs, void* state); + + inline status_t sort(compar_t cmp); + inline status_t sort(compar_r_t cmp, void* state); + + // for debugging only + inline size_t getItemSize() const { return itemSize(); } + + + /* + * these inlines add some level of compatibility with STL. eventually + * we should probably turn things around. + */ + typedef TYPE* iterator; + typedef TYPE const* const_iterator; + + inline iterator begin() { return editArray(); } + inline iterator end() { return editArray() + size(); } + inline const_iterator begin() const { return array(); } + inline const_iterator end() const { return array() + size(); } + inline void reserve(size_t n) { setCapacity(n); } + inline bool empty() const{ return isEmpty(); } + inline void push_back(const TYPE& item) { insertAt(item, size(), 1); } + inline void push_front(const TYPE& item) { insertAt(item, 0, 1); } + inline iterator erase(iterator pos) { + ssize_t index = removeItemsAt(pos-array()); + return begin() + index; + } + +protected: + virtual void do_construct(void* storage, size_t num) const; + virtual void do_destroy(void* storage, size_t num) const; + virtual void do_copy(void* dest, const void* from, size_t num) const; + virtual void do_splat(void* dest, const void* item, size_t num) const; + virtual void do_move_forward(void* dest, const void* from, size_t num) const; + virtual void do_move_backward(void* dest, const void* from, size_t num) const; +}; + +// Vector can be trivially moved using memcpy() because moving does not +// require any change to the underlying SharedBuffer contents or reference count. +template struct trait_trivial_move > { enum { value = true }; }; + +// --------------------------------------------------------------------------- +// No user serviceable parts from here... +// --------------------------------------------------------------------------- + +template inline +Vector::Vector() + : VectorImpl(sizeof(TYPE), + ((traits::has_trivial_ctor ? HAS_TRIVIAL_CTOR : 0) + |(traits::has_trivial_dtor ? HAS_TRIVIAL_DTOR : 0) + |(traits::has_trivial_copy ? HAS_TRIVIAL_COPY : 0)) + ) +{ +} + +template inline +Vector::Vector(const Vector& rhs) + : VectorImpl(rhs) { +} + +template inline +Vector::Vector(const SortedVector& rhs) + : VectorImpl(static_cast(rhs)) { +} + +template inline +Vector::~Vector() { + finish_vector(); +} + +template inline +Vector& Vector::operator = (const Vector& rhs) { + VectorImpl::operator = (rhs); + return *this; +} + +template inline +const Vector& Vector::operator = (const Vector& rhs) const { + VectorImpl::operator = (static_cast(rhs)); + return *this; +} + +template inline +Vector& Vector::operator = (const SortedVector& rhs) { + VectorImpl::operator = (static_cast(rhs)); + return *this; +} + +template inline +const Vector& Vector::operator = (const SortedVector& rhs) const { + VectorImpl::operator = (rhs); + return *this; +} + +template inline +const TYPE* Vector::array() const { + return static_cast(arrayImpl()); +} + +template inline +TYPE* Vector::editArray() { + return static_cast(editArrayImpl()); +} + + +template inline +const TYPE& Vector::operator[](size_t index) const { + LOG_FATAL_IF(index>=size(), + "%s: index=%u out of range (%u)", __PRETTY_FUNCTION__, + int(index), int(size())); + return *(array() + index); +} + +template inline +const TYPE& Vector::itemAt(size_t index) const { + return operator[](index); +} + +template inline +const TYPE& Vector::top() const { + return *(array() + size() - 1); +} + +template inline +TYPE& Vector::editItemAt(size_t index) { + return *( static_cast(editItemLocation(index)) ); +} + +template inline +TYPE& Vector::editTop() { + return *( static_cast(editItemLocation(size()-1)) ); +} + +template inline +ssize_t Vector::insertVectorAt(const Vector& vector, size_t index) { + return VectorImpl::insertVectorAt(reinterpret_cast(vector), index); +} + +template inline +ssize_t Vector::appendVector(const Vector& vector) { + return VectorImpl::appendVector(reinterpret_cast(vector)); +} + +template inline +ssize_t Vector::insertArrayAt(const TYPE* array, size_t index, size_t length) { + return VectorImpl::insertArrayAt(array, index, length); +} + +template inline +ssize_t Vector::appendArray(const TYPE* array, size_t length) { + return VectorImpl::appendArray(array, length); +} + +template inline +ssize_t Vector::insertAt(const TYPE& item, size_t index, size_t numItems) { + return VectorImpl::insertAt(&item, index, numItems); +} + +template inline +void Vector::push(const TYPE& item) { + return VectorImpl::push(&item); +} + +template inline +ssize_t Vector::add(const TYPE& item) { + return VectorImpl::add(&item); +} + +template inline +ssize_t Vector::replaceAt(const TYPE& item, size_t index) { + return VectorImpl::replaceAt(&item, index); +} + +template inline +ssize_t Vector::insertAt(size_t index, size_t numItems) { + return VectorImpl::insertAt(index, numItems); +} + +template inline +void Vector::pop() { + VectorImpl::pop(); +} + +template inline +void Vector::push() { + VectorImpl::push(); +} + +template inline +ssize_t Vector::add() { + return VectorImpl::add(); +} + +template inline +ssize_t Vector::replaceAt(size_t index) { + return VectorImpl::replaceAt(index); +} + +template inline +ssize_t Vector::removeItemsAt(size_t index, size_t count) { + return VectorImpl::removeItemsAt(index, count); +} + +template inline +status_t Vector::sort(Vector::compar_t cmp) { + return VectorImpl::sort((VectorImpl::compar_t)cmp); +} + +template inline +status_t Vector::sort(Vector::compar_r_t cmp, void* state) { + return VectorImpl::sort((VectorImpl::compar_r_t)cmp, state); +} + +// --------------------------------------------------------------------------- + +template +void Vector::do_construct(void* storage, size_t num) const { + construct_type( reinterpret_cast(storage), num ); +} + +template +void Vector::do_destroy(void* storage, size_t num) const { + destroy_type( reinterpret_cast(storage), num ); +} + +template +void Vector::do_copy(void* dest, const void* from, size_t num) const { + copy_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +template +void Vector::do_splat(void* dest, const void* item, size_t num) const { + splat_type( reinterpret_cast(dest), reinterpret_cast(item), num ); +} + +template +void Vector::do_move_forward(void* dest, const void* from, size_t num) const { + move_forward_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +template +void Vector::do_move_backward(void* dest, const void* from, size_t num) const { + move_backward_type( reinterpret_cast(dest), reinterpret_cast(from), num ); +} + +}; // namespace android + + +// --------------------------------------------------------------------------- + +#endif // ANDROID_VECTOR_H diff --git a/third_party/android_system_core/include/utils/VectorImpl.h b/third_party/android_system_core/include/utils/VectorImpl.h new file mode 100644 index 00000000000000..21ad71ce607534 --- /dev/null +++ b/third_party/android_system_core/include/utils/VectorImpl.h @@ -0,0 +1,183 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef ANDROID_VECTOR_IMPL_H +#define ANDROID_VECTOR_IMPL_H + +#include +#include +#include +#include + +// --------------------------------------------------------------------------- +// No user serviceable parts in here... +// --------------------------------------------------------------------------- + +namespace android { + +/*! + * Implementation of the guts of the vector<> class + * this ensures backward binary compatibility and + * reduces code size. + * For performance reasons, we expose mStorage and mCount + * so these fields are set in stone. + * + */ + +class VectorImpl +{ +public: + enum { // flags passed to the ctor + HAS_TRIVIAL_CTOR = 0x00000001, + HAS_TRIVIAL_DTOR = 0x00000002, + HAS_TRIVIAL_COPY = 0x00000004, + }; + + VectorImpl(size_t itemSize, uint32_t flags); + VectorImpl(const VectorImpl& rhs); + virtual ~VectorImpl(); + + /*! must be called from subclasses destructor */ + void finish_vector(); + + VectorImpl& operator = (const VectorImpl& rhs); + + /*! C-style array access */ + inline const void* arrayImpl() const { return mStorage; } + void* editArrayImpl(); + + /*! vector stats */ + inline size_t size() const { return mCount; } + inline bool isEmpty() const { return mCount == 0; } + size_t capacity() const; + ssize_t setCapacity(size_t size); + ssize_t resize(size_t size); + + /*! append/insert another vector or array */ + ssize_t insertVectorAt(const VectorImpl& vector, size_t index); + ssize_t appendVector(const VectorImpl& vector); + ssize_t insertArrayAt(const void* array, size_t index, size_t length); + ssize_t appendArray(const void* array, size_t length); + + /*! add/insert/replace items */ + ssize_t insertAt(size_t where, size_t numItems = 1); + ssize_t insertAt(const void* item, size_t where, size_t numItems = 1); + void pop(); + void push(); + void push(const void* item); + ssize_t add(); + ssize_t add(const void* item); + ssize_t replaceAt(size_t index); + ssize_t replaceAt(const void* item, size_t index); + + /*! remove items */ + ssize_t removeItemsAt(size_t index, size_t count = 1); + void clear(); + + const void* itemLocation(size_t index) const; + void* editItemLocation(size_t index); + + typedef int (*compar_t)(const void* lhs, const void* rhs); + typedef int (*compar_r_t)(const void* lhs, const void* rhs, void* state); + status_t sort(compar_t cmp); + status_t sort(compar_r_t cmp, void* state); + +protected: + size_t itemSize() const; + void release_storage(); + + virtual void do_construct(void* storage, size_t num) const = 0; + virtual void do_destroy(void* storage, size_t num) const = 0; + virtual void do_copy(void* dest, const void* from, size_t num) const = 0; + virtual void do_splat(void* dest, const void* item, size_t num) const = 0; + virtual void do_move_forward(void* dest, const void* from, size_t num) const = 0; + virtual void do_move_backward(void* dest, const void* from, size_t num) const = 0; + +private: + void* _grow(size_t where, size_t amount); + void _shrink(size_t where, size_t amount); + + inline void _do_construct(void* storage, size_t num) const; + inline void _do_destroy(void* storage, size_t num) const; + inline void _do_copy(void* dest, const void* from, size_t num) const; + inline void _do_splat(void* dest, const void* item, size_t num) const; + inline void _do_move_forward(void* dest, const void* from, size_t num) const; + inline void _do_move_backward(void* dest, const void* from, size_t num) const; + + // These 2 fields are exposed in the inlines below, + // so they're set in stone. + void * mStorage; // base address of the vector + size_t mCount; // number of items + + const uint32_t mFlags; + const size_t mItemSize; +}; + + + +class SortedVectorImpl : public VectorImpl +{ +public: + SortedVectorImpl(size_t itemSize, uint32_t flags); + SortedVectorImpl(const VectorImpl& rhs); + virtual ~SortedVectorImpl(); + + SortedVectorImpl& operator = (const SortedVectorImpl& rhs); + + //! finds the index of an item + ssize_t indexOf(const void* item) const; + + //! finds where this item should be inserted + size_t orderOf(const void* item) const; + + //! add an item in the right place (or replaces it if there is one) + ssize_t add(const void* item); + + //! merges a vector into this one + ssize_t merge(const VectorImpl& vector); + ssize_t merge(const SortedVectorImpl& vector); + + //! removes an item + ssize_t remove(const void* item); + +protected: + virtual int do_compare(const void* lhs, const void* rhs) const = 0; + +private: + ssize_t _indexOrderOf(const void* item, size_t* order = 0) const; + + // these are made private, because they can't be used on a SortedVector + // (they don't have an implementation either) + ssize_t add(); + void pop(); + void push(); + void push(const void* item); + ssize_t insertVectorAt(const VectorImpl& vector, size_t index); + ssize_t appendVector(const VectorImpl& vector); + ssize_t insertArrayAt(const void* array, size_t index, size_t length); + ssize_t appendArray(const void* array, size_t length); + ssize_t insertAt(size_t where, size_t numItems = 1); + ssize_t insertAt(const void* item, size_t where, size_t numItems = 1); + ssize_t replaceAt(size_t index); + ssize_t replaceAt(const void* item, size_t index); +}; + +}; // namespace android + + +// --------------------------------------------------------------------------- + +#endif // ANDROID_VECTOR_IMPL_H diff --git a/third_party/android_system_core/include/utils/ashmem.h b/third_party/android_system_core/include/utils/ashmem.h new file mode 100644 index 00000000000000..0854775780f9e9 --- /dev/null +++ b/third_party/android_system_core/include/utils/ashmem.h @@ -0,0 +1,41 @@ +/* utils/ashmem.h + ** + ** Copyright 2008 The Android Open Source Project + ** + ** This file is dual licensed. It may be redistributed and/or modified + ** under the terms of the Apache 2.0 License OR version 2 of the GNU + ** General Public License. + */ + +#ifndef _UTILS_ASHMEM_H +#define _UTILS_ASHMEM_H + +#include +#include + +#define ASHMEM_NAME_LEN 256 + +#define ASHMEM_NAME_DEF "dev/ashmem" + +/* Return values from ASHMEM_PIN: Was the mapping purged while unpinned? */ +#define ASHMEM_NOT_REAPED 0 +#define ASHMEM_WAS_REAPED 1 + +/* Return values from ASHMEM_UNPIN: Is the mapping now pinned or unpinned? */ +#define ASHMEM_NOW_UNPINNED 0 +#define ASHMEM_NOW_PINNED 1 + +#define __ASHMEMIOC 0x77 + +#define ASHMEM_SET_NAME _IOW(__ASHMEMIOC, 1, char[ASHMEM_NAME_LEN]) +#define ASHMEM_GET_NAME _IOR(__ASHMEMIOC, 2, char[ASHMEM_NAME_LEN]) +#define ASHMEM_SET_SIZE _IOW(__ASHMEMIOC, 3, size_t) +#define ASHMEM_GET_SIZE _IO(__ASHMEMIOC, 4) +#define ASHMEM_SET_PROT_MASK _IOW(__ASHMEMIOC, 5, unsigned long) +#define ASHMEM_GET_PROT_MASK _IO(__ASHMEMIOC, 6) +#define ASHMEM_PIN _IO(__ASHMEMIOC, 7) +#define ASHMEM_UNPIN _IO(__ASHMEMIOC, 8) +#define ASHMEM_ISPINNED _IO(__ASHMEMIOC, 9) +#define ASHMEM_PURGE_ALL_CACHES _IO(__ASHMEMIOC, 10) + +#endif /* _UTILS_ASHMEM_H */ diff --git a/third_party/android_system_core/include/utils/misc.h b/third_party/android_system_core/include/utils/misc.h new file mode 100644 index 00000000000000..6cccec387d1102 --- /dev/null +++ b/third_party/android_system_core/include/utils/misc.h @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2005 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// +// Handy utility functions and portability code. +// +#ifndef _LIBS_UTILS_MISC_H +#define _LIBS_UTILS_MISC_H + +#include + +/* get #of elements in a static array */ +#ifndef NELEM +# define NELEM(x) ((int) (sizeof(x) / sizeof((x)[0]))) +#endif + +namespace android { + +typedef void (*sysprop_change_callback)(void); +void add_sysprop_change_callback(sysprop_change_callback cb, int priority); +void report_sysprop_change(); + +}; // namespace android + +#endif // _LIBS_UTILS_MISC_H diff --git a/third_party/android_system_core/include/utils/threads.h b/third_party/android_system_core/include/utils/threads.h new file mode 100644 index 00000000000000..9de3382118697f --- /dev/null +++ b/third_party/android_system_core/include/utils/threads.h @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2007 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _LIBS_UTILS_THREADS_H +#define _LIBS_UTILS_THREADS_H + +/* + * Please, DO NOT USE! + * + * This file is here only for legacy reasons. Instead, include directly + * the headers you need below. + * + */ + +#include + +#ifdef __cplusplus +#include +#include +#include +#include +#include +#endif + +#endif // _LIBS_UTILS_THREADS_H diff --git a/third_party/libgralloc/include/gralloc_priv.h b/third_party/libgralloc/include/gralloc_priv.h new file mode 100644 index 00000000000000..4aa47541b03c04 --- /dev/null +++ b/third_party/libgralloc/include/gralloc_priv.h @@ -0,0 +1,296 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * Copyright (c) 2011-2015, The Linux Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef GRALLOC_PRIV_H_ +#define GRALLOC_PRIV_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#define ROUND_UP_PAGESIZE(x) ( (((unsigned long)(x)) + PAGE_SIZE-1) & \ + (~(PAGE_SIZE-1)) ) + +/* Gralloc usage bits indicating the type of allocation that should be used */ +/* SYSTEM heap comes from kernel vmalloc (ION_SYSTEM_HEAP_ID) + * is cached by default and + * is not secured */ + +/* GRALLOC_USAGE_PRIVATE_0 is unused */ + +/* Non linear, Universal Bandwidth Compression */ +#define GRALLOC_USAGE_PRIVATE_ALLOC_UBWC GRALLOC_USAGE_PRIVATE_1 + +/* IOMMU heap comes from manually allocated pages, can be cached/uncached, + * is not secured */ +#define GRALLOC_USAGE_PRIVATE_IOMMU_HEAP GRALLOC_USAGE_PRIVATE_2 + +/* MM heap is a carveout heap for video, can be secured */ +#define GRALLOC_USAGE_PRIVATE_MM_HEAP GRALLOC_USAGE_PRIVATE_3 + +/* ADSP heap is a carveout heap, is not secured */ +#define GRALLOC_USAGE_PRIVATE_ADSP_HEAP 0x01000000 + +/* Set this for allocating uncached memory (using O_DSYNC), + * cannot be used with noncontiguous heaps */ +#define GRALLOC_USAGE_PRIVATE_UNCACHED 0x02000000 + +/* Buffer content should be displayed on an primary display only */ +#define GRALLOC_USAGE_PRIVATE_INTERNAL_ONLY 0x04000000 + +/* Buffer content should be displayed on an external display only */ +#define GRALLOC_USAGE_PRIVATE_EXTERNAL_ONLY 0x08000000 + +/* This flag is set for WFD usecase */ +#define GRALLOC_USAGE_PRIVATE_WFD 0x00200000 + +/* CAMERA heap is a carveout heap for camera, is not secured */ +#define GRALLOC_USAGE_PRIVATE_CAMERA_HEAP 0x00400000 + +/* This flag is used for SECURE display usecase */ +#define GRALLOC_USAGE_PRIVATE_SECURE_DISPLAY 0x00800000 + +/* define Gralloc perform */ +#define GRALLOC_MODULE_PERFORM_CREATE_HANDLE_FROM_BUFFER 1 +// This will be used by the graphics drivers to know if certain features +// are defined in this display HAL. +// Ex: Newer GFX libraries + Older Display HAL +#define GRALLOC_MODULE_PERFORM_GET_STRIDE 2 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_FROM_HANDLE 3 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_AND_HEIGHT_FROM_HANDLE 4 +#define GRALLOC_MODULE_PERFORM_GET_ATTRIBUTES 5 +#define GRALLOC_MODULE_PERFORM_GET_COLOR_SPACE_FROM_HANDLE 6 +#define GRALLOC_MODULE_PERFORM_GET_YUV_PLANE_INFO 7 +#define GRALLOC_MODULE_PERFORM_GET_MAP_SECURE_BUFFER_INFO 8 +#define GRALLOC_MODULE_PERFORM_GET_UBWC_FLAG 9 +#define GRALLOC_MODULE_PERFORM_GET_RGB_DATA_ADDRESS 10 +#define GRALLOC_MODULE_PERFORM_GET_IGC 11 +#define GRALLOC_MODULE_PERFORM_SET_IGC 12 +#define GRALLOC_MODULE_PERFORM_SET_SINGLE_BUFFER_MODE 13 + +/* OEM specific HAL formats */ + +#define HAL_PIXEL_FORMAT_RGBA_5551 6 +#define HAL_PIXEL_FORMAT_RGBA_4444 7 +#define HAL_PIXEL_FORMAT_NV12_ENCODEABLE 0x102 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS 0x7FA30C04 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_TILED 0x7FA30C03 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP 0x109 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_ADRENO 0x7FA30C01 +#define HAL_PIXEL_FORMAT_YCrCb_422_SP 0x10B +#define HAL_PIXEL_FORMAT_R_8 0x10D +#define HAL_PIXEL_FORMAT_RG_88 0x10E +#define HAL_PIXEL_FORMAT_YCbCr_444_SP 0x10F +#define HAL_PIXEL_FORMAT_YCrCb_444_SP 0x110 +#define HAL_PIXEL_FORMAT_YCrCb_422_I 0x111 +#define HAL_PIXEL_FORMAT_BGRX_8888 0x112 +#define HAL_PIXEL_FORMAT_NV21_ZSL 0x113 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_VENUS 0x114 +#define HAL_PIXEL_FORMAT_BGR_565 0x115 +#define HAL_PIXEL_FORMAT_INTERLACE 0x180 + +//v4l2_fourcc('Y', 'U', 'Y', 'L'). 24 bpp YUYV 4:2:2 10 bit per component +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT 0x4C595559 + +//v4l2_fourcc('Y', 'B', 'W', 'C'). 10 bit per component. This compressed +//format reduces the memory access bandwidth +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT_COMPRESSED 0x43574259 + +// UBWC aligned Venus format +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS_UBWC 0x7FA30C06 + +//Khronos ASTC formats +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_4x4_KHR 0x93B0 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x4_KHR 0x93B1 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x5_KHR 0x93B2 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x5_KHR 0x93B3 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x6_KHR 0x93B4 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x5_KHR 0x93B5 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x6_KHR 0x93B6 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x8_KHR 0x93B7 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x5_KHR 0x93B8 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x6_KHR 0x93B9 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x8_KHR 0x93BA +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x10_KHR 0x93BB +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x10_KHR 0x93BC +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x12_KHR 0x93BD +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_4x4_KHR 0x93D0 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x4_KHR 0x93D1 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x5_KHR 0x93D2 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x5_KHR 0x93D3 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x6_KHR 0x93D4 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x5_KHR 0x93D5 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x6_KHR 0x93D6 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x8_KHR 0x93D7 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x5_KHR 0x93D8 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x6_KHR 0x93D9 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x8_KHR 0x93DA +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x10_KHR 0x93DB +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x10_KHR 0x93DC +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x12_KHR 0x93DD + +/* possible values for inverse gamma correction */ +#define HAL_IGC_NOT_SPECIFIED 0 +#define HAL_IGC_s_RGB 1 + +/* possible formats for 3D content*/ +enum { + HAL_NO_3D = 0x0, + HAL_3D_SIDE_BY_SIDE_L_R = 0x1, + HAL_3D_SIDE_BY_SIDE_R_L = 0x2, + HAL_3D_TOP_BOTTOM = 0x4, + HAL_3D_IN_SIDE_BY_SIDE_L_R = 0x10000, //unused legacy format +}; + +enum { + BUFFER_TYPE_UI = 0, + BUFFER_TYPE_VIDEO +}; + +#ifdef __cplusplus +struct private_handle_t : public native_handle { +#else + struct private_handle_t { + native_handle_t nativeHandle; +#endif + enum { + PRIV_FLAGS_FRAMEBUFFER = 0x00000001, + PRIV_FLAGS_USES_ION = 0x00000008, + PRIV_FLAGS_USES_ASHMEM = 0x00000010, + PRIV_FLAGS_NEEDS_FLUSH = 0x00000020, + PRIV_FLAGS_INTERNAL_ONLY = 0x00000040, + PRIV_FLAGS_NON_CPU_WRITER = 0x00000080, + PRIV_FLAGS_NONCONTIGUOUS_MEM = 0x00000100, + PRIV_FLAGS_CACHED = 0x00000200, + PRIV_FLAGS_SECURE_BUFFER = 0x00000400, + // Display on external only + PRIV_FLAGS_EXTERNAL_ONLY = 0x00002000, + // Set by HWC for protected non secure buffers + PRIV_FLAGS_PROTECTED_BUFFER = 0x00004000, + PRIV_FLAGS_VIDEO_ENCODER = 0x00010000, + PRIV_FLAGS_CAMERA_WRITE = 0x00020000, + PRIV_FLAGS_CAMERA_READ = 0x00040000, + PRIV_FLAGS_HW_COMPOSER = 0x00080000, + PRIV_FLAGS_HW_TEXTURE = 0x00100000, + PRIV_FLAGS_ITU_R_601 = 0x00200000, //Unused from display + PRIV_FLAGS_ITU_R_601_FR = 0x00400000, //Unused from display + PRIV_FLAGS_ITU_R_709 = 0x00800000, //Unused from display + PRIV_FLAGS_SECURE_DISPLAY = 0x01000000, + // Buffer is rendered in Tile Format + PRIV_FLAGS_TILE_RENDERED = 0x02000000, + // Buffer rendered using CPU/SW renderer + PRIV_FLAGS_CPU_RENDERED = 0x04000000, + // Buffer is allocated with UBWC alignment + PRIV_FLAGS_UBWC_ALIGNED = 0x08000000, + // Buffer allocated will be consumed by SF/HWC + PRIV_FLAGS_DISP_CONSUMER = 0x10000000 + }; + + // file-descriptors + int fd; + int fd_metadata; // fd for the meta-data + // ints + int magic; + int flags; + unsigned int size; + unsigned int offset; + int bufferType; + uint64_t base __attribute__((aligned(8))); + unsigned int offset_metadata; + // The gpu address mapped into the mmu. + uint64_t gpuaddr __attribute__((aligned(8))); + int format; + int width; // specifies aligned width + int height; // specifies aligned height + int real_width; + int real_height; + uint64_t base_metadata __attribute__((aligned(8))); + +#ifdef __cplusplus + static const int sNumFds = 2; + static inline int sNumInts() { + return ((sizeof(private_handle_t) - sizeof(native_handle_t)) / + sizeof(int)) - sNumFds; + } + static const int sMagic = 'gmsm'; + + private_handle_t(int fd, unsigned int size, int flags, int bufferType, + int format, int aligned_width, int aligned_height, + int width, int height, int eFd = -1, + unsigned int eOffset = 0, uint64_t eBase = 0) : + fd(fd), fd_metadata(eFd), magic(sMagic), + flags(flags), size(size), offset(0), bufferType(bufferType), + base(0), offset_metadata(eOffset), gpuaddr(0), + format(format), width(aligned_width), height(aligned_height), + real_width(width), real_height(height), base_metadata(eBase) + { + version = (int) sizeof(native_handle); + numInts = sNumInts(); + numFds = sNumFds; + } + ~private_handle_t() { + magic = 0; + } + + static int validate(const native_handle* h) { + const private_handle_t* hnd = (const private_handle_t*)h; + if (!h || h->version != sizeof(native_handle) || + h->numInts != sNumInts() || h->numFds != sNumFds || + hnd->magic != sMagic) + { + ALOGD("Invalid gralloc handle (at %p): " + "ver(%d/%zu) ints(%d/%d) fds(%d/%d)" + "magic(%c%c%c%c/%c%c%c%c)", + h, + h ? h->version : -1, sizeof(native_handle), + h ? h->numInts : -1, sNumInts(), + h ? h->numFds : -1, sNumFds, + hnd ? (((hnd->magic >> 24) & 0xFF)? + ((hnd->magic >> 24) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 16) & 0xFF)? + ((hnd->magic >> 16) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 8) & 0xFF)? + ((hnd->magic >> 8) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 0) & 0xFF)? + ((hnd->magic >> 0) & 0xFF) : '-') : '?', + (sMagic >> 24) & 0xFF, + (sMagic >> 16) & 0xFF, + (sMagic >> 8) & 0xFF, + (sMagic >> 0) & 0xFF); + return -EINVAL; + } + return 0; + } + + static private_handle_t* dynamicCast(const native_handle* in) { + if (validate(in) == 0) { + return (private_handle_t*) in; + } + return NULL; + } +#endif + }; + +#endif /* GRALLOC_PRIV_H_ */ diff --git a/third_party/snpe/aarch64 b/third_party/snpe/aarch64 new file mode 120000 index 00000000000000..baf4e9cb6ed759 --- /dev/null +++ b/third_party/snpe/aarch64 @@ -0,0 +1 @@ +aarch64-android-clang6.0 \ No newline at end of file diff --git a/third_party/snpe/aarch64-android-clang6.0/libPlatformValidatorShared.so b/third_party/snpe/aarch64-android-clang6.0/libPlatformValidatorShared.so new file mode 100644 index 00000000000000..5df5b07b18bb15 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libPlatformValidatorShared.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libSNPE.so b/third_party/snpe/aarch64-android-clang6.0/libSNPE.so new file mode 100644 index 00000000000000..6ef777e15b77d1 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libSNPE.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libSNPE_G.so b/third_party/snpe/aarch64-android-clang6.0/libSNPE_G.so new file mode 100644 index 00000000000000..565c80bb68c5ce Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libSNPE_G.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libc++_shared.so b/third_party/snpe/aarch64-android-clang6.0/libc++_shared.so new file mode 100644 index 00000000000000..5b9a9cff612be4 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libc++_shared.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libcalculator.so b/third_party/snpe/aarch64-android-clang6.0/libcalculator.so new file mode 100644 index 00000000000000..3aa1ec3ac27cc6 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libcalculator.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libcalculator_domains.so b/third_party/snpe/aarch64-android-clang6.0/libcalculator_domains.so new file mode 100644 index 00000000000000..bef3fc20192cf6 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libcalculator_domains.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libhta.so b/third_party/snpe/aarch64-android-clang6.0/libhta.so new file mode 100644 index 00000000000000..bfd3554cf78b14 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libhta.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsnpe_adsp.so b/third_party/snpe/aarch64-android-clang6.0/libsnpe_adsp.so new file mode 100644 index 00000000000000..8a6b4e3fc5a085 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsnpe_adsp.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains.so b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains.so new file mode 100644 index 00000000000000..0663d25e3378ad Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_system.so b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_system.so new file mode 100644 index 00000000000000..33d354ff7d4764 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_system.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2.so b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2.so new file mode 100644 index 00000000000000..5a63344590a106 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2_system.so b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2_system.so new file mode 100644 index 00000000000000..2d74ae0f055f9c Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsnpe_dsp_domains_v2_system.so differ diff --git a/third_party/snpe/aarch64-android-clang6.0/libsymphony-cpu.so b/third_party/snpe/aarch64-android-clang6.0/libsymphony-cpu.so new file mode 100644 index 00000000000000..8dd26fb26664d7 Binary files /dev/null and b/third_party/snpe/aarch64-android-clang6.0/libsymphony-cpu.so differ diff --git a/tools/ssh/README.md b/tools/ssh/README.md index 66f030de5284e3..5c7f3519b22abd 100644 --- a/tools/ssh/README.md +++ b/tools/ssh/README.md @@ -7,7 +7,7 @@ In order to SSH into your device, you'll need a GitHub account with SSH keys. Se * Enable SSH in your device's settings * Enter your GitHub username in the device's settings * Connect to your device - * Username: `comma` (comma three) + * Username: `root` (comma two) or `comma` (comma three) * Port: `22` or `8022` Here's an example command for connecting to your device using its tethered connection: