From 24b5164ce610fdfe8d6d7a9ea83edf960a25a6d8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 29 Apr 2022 18:23:47 -0700 Subject: [PATCH 001/391] Subaru: Add fwdCamera FW for 2018 Crosstrek (#24377) --- selfdrive/car/subaru/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 4b6f3604b3..2aca2af576 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -121,6 +121,7 @@ FW_VERSIONS = { b'\x00\x00d)\x00\x00\x00\x00', b'\x00\x00c\xf4\x00\x00\x00\x00', b'\x00\x00d\xdc\x00\x00\x00\x00', + b'\x00\x00dd\x00\x00\x00\x00', ], (Ecu.engine, 0x7e0, None): [ b'\xaa\x61\x66\x73\x07', From 7b394510cb9e564803b70139eed0e6a07103d0c7 Mon Sep 17 00:00:00 2001 From: Keyvan Fatehi Date: Fri, 29 Apr 2022 20:13:44 -0700 Subject: [PATCH 002/391] Fix spelling in dump.py help output (#24381) --- selfdrive/debug/dump.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index f208920f12..fdb825eead 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -13,7 +13,7 @@ from cereal.services import service_list if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Dump communcation sockets. See cereal/services.py for a complete list of available sockets.') + parser = argparse.ArgumentParser(description='Dump communication sockets. See cereal/services.py for a complete list of available sockets.') parser.add_argument('--pipe', action='store_true') parser.add_argument('--raw', action='store_true') parser.add_argument('--json', action='store_true') From 0baa4c3e2ad9ee6f8daba8267db44c2cd44caa62 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Sat, 30 Apr 2022 09:22:52 -0700 Subject: [PATCH 003/391] loggerd: switch to v4l encoder try 2 (#24380) * start v4l encoder * v4l encoder starts * start and stop * fill in proper controls * it dequeued a buffer * getting bytes * it made a video * it does make files * getting close * ahh, so that's how dequeue works * qcam works (no remuxing) * remuxing works * we just need to make shutdown and rollover graceful * graceful destruction * switch to polling * should work now * fix pc build * refactors, stop properly * touchups, remove a copy * add v4l encoder to release * inlcude file * move writing to it's own thread * fix minor memory leak * block instead of dropping frames * add counter, fix tests maybe * better debugging and test print * print file path in assert * format string in test * no more oversized qlogs * match qcam * touchups, remove omx encoder * remove omx include files * checked ioctl, better debugging, open by name * unused import * move linux includes to third_party/linux/include * simple encoderd * full packet * encoderd should be complete * lagging print * updates * name dq thread * subset idx * video file writing works * debug * potential bugfix * rotation works * iframe * keep writing support * ci should pass * loggerd, not encoderd * remote encoder code * support remote encoder * cereal to master, add encoderd * header no longer required * put that back there * realtime * lower decoder latency * don't use queue for VisionIpcBufExtra, disable realtime again * assert all written * hmm simpler * only push to to_write if we are writing * assert timestamp is right * use at and remove assert * revert to queue Co-authored-by: Comma Device --- SConstruct | 1 - cereal | 2 +- release/files_common | 9 +- selfdrive/loggerd/.gitignore | 1 + selfdrive/loggerd/SConscript | 10 +- selfdrive/loggerd/encoder.h | 4 +- selfdrive/loggerd/encoderd.cc | 145 ++ selfdrive/loggerd/loggerd.cc | 21 +- selfdrive/loggerd/loggerd.h | 12 +- selfdrive/loggerd/omx_encoder.cc | 547 ----- selfdrive/loggerd/omx_encoder.h | 79 - selfdrive/loggerd/raw_logger.cc | 2 +- selfdrive/loggerd/raw_logger.h | 3 +- selfdrive/loggerd/remote_encoder.cc | 84 + selfdrive/loggerd/remote_encoder.h | 12 + selfdrive/loggerd/tests/test_encoder.py | 3 +- selfdrive/loggerd/v4l_encoder.cc | 401 ++++ selfdrive/loggerd/v4l_encoder.h | 48 + selfdrive/loggerd/video_writer.cc | 1 - selfdrive/loggerd/video_writer.h | 2 - .../linux}/include/msm_media_info.h | 0 third_party/linux/include/v4l2-controls.h | 1696 +++++++++++++++ third_party/openmax/include/OMX_Audio.h | 1312 ------------ third_party/openmax/include/OMX_Component.h | 579 ----- third_party/openmax/include/OMX_ContentPipe.h | 195 -- third_party/openmax/include/OMX_Core.h | 1440 ------------- third_party/openmax/include/OMX_CoreExt.h | 66 - third_party/openmax/include/OMX_IVCommon.h | 933 -------- third_party/openmax/include/OMX_Image.h | 328 --- third_party/openmax/include/OMX_Index.h | 259 --- third_party/openmax/include/OMX_IndexExt.h | 95 - third_party/openmax/include/OMX_Other.h | 337 --- third_party/openmax/include/OMX_QCOMExtns.h | 1888 ----------------- .../include/OMX_Skype_VideoExtensions.h | 155 -- third_party/openmax/include/OMX_Types.h | 359 ---- third_party/openmax/include/OMX_Video.h | 1082 ---------- third_party/openmax/include/OMX_VideoExt.h | 166 -- tools/camerastream/compressed_vipc.py | 26 +- 38 files changed, 2445 insertions(+), 9858 deletions(-) create mode 100644 selfdrive/loggerd/encoderd.cc delete mode 100644 selfdrive/loggerd/omx_encoder.cc delete mode 100644 selfdrive/loggerd/omx_encoder.h create mode 100644 selfdrive/loggerd/remote_encoder.cc create mode 100644 selfdrive/loggerd/remote_encoder.h create mode 100644 selfdrive/loggerd/v4l_encoder.cc create mode 100644 selfdrive/loggerd/v4l_encoder.h rename {selfdrive/loggerd => third_party/linux}/include/msm_media_info.h (100%) create mode 100644 third_party/linux/include/v4l2-controls.h delete mode 100644 third_party/openmax/include/OMX_Audio.h delete mode 100644 third_party/openmax/include/OMX_Component.h delete mode 100644 third_party/openmax/include/OMX_ContentPipe.h delete mode 100644 third_party/openmax/include/OMX_Core.h delete mode 100644 third_party/openmax/include/OMX_CoreExt.h delete mode 100644 third_party/openmax/include/OMX_IVCommon.h delete mode 100644 third_party/openmax/include/OMX_Image.h delete mode 100644 third_party/openmax/include/OMX_Index.h delete mode 100644 third_party/openmax/include/OMX_IndexExt.h delete mode 100644 third_party/openmax/include/OMX_Other.h delete mode 100644 third_party/openmax/include/OMX_QCOMExtns.h delete mode 100644 third_party/openmax/include/OMX_Skype_VideoExtensions.h delete mode 100644 third_party/openmax/include/OMX_Types.h delete mode 100644 third_party/openmax/include/OMX_Video.h delete mode 100644 third_party/openmax/include/OMX_VideoExt.h diff --git a/SConstruct b/SConstruct index 48a5e0e2af..520716859a 100644 --- a/SConstruct +++ b/SConstruct @@ -184,7 +184,6 @@ env = Environment( "#third_party/acados/include/hpipm/include", "#third_party/catch2/include", "#third_party/libyuv/include", - "#third_party/openmax/include", "#third_party/json11", "#third_party/curl/include", "#third_party/libgralloc/include", diff --git a/cereal b/cereal index a057aed167..aea23111ee 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit a057aed16747d0e414145d83d4861c50315781ad +Subproject commit aea23111ee0a08efb549d1d318405b9af8f456d9 diff --git a/release/files_common b/release/files_common index 1592fcf8ad..c44f10229e 100644 --- a/release/files_common +++ b/release/files_common @@ -299,19 +299,21 @@ selfdrive/proclogd/proclog.h selfdrive/loggerd/SConscript selfdrive/loggerd/encoder.h -selfdrive/loggerd/omx_encoder.cc -selfdrive/loggerd/omx_encoder.h +selfdrive/loggerd/v4l_encoder.cc +selfdrive/loggerd/v4l_encoder.h selfdrive/loggerd/video_writer.cc selfdrive/loggerd/video_writer.h +selfdrive/loggerd/remote_encoder.cc +selfdrive/loggerd/remote_encoder.h selfdrive/loggerd/logger.cc selfdrive/loggerd/logger.h selfdrive/loggerd/loggerd.cc selfdrive/loggerd/loggerd.h +selfdrive/loggerd/encoderd.cc selfdrive/loggerd/main.cc selfdrive/loggerd/bootlog.cc selfdrive/loggerd/raw_logger.cc selfdrive/loggerd/raw_logger.h -selfdrive/loggerd/include/msm_media_info.h selfdrive/loggerd/__init__.py selfdrive/loggerd/config.py @@ -444,7 +446,6 @@ third_party/SConscript third_party/linux/** third_party/opencl/** -third_party/openmax/** third_party/json11/json11.cpp third_party/json11/json11.hpp diff --git a/selfdrive/loggerd/.gitignore b/selfdrive/loggerd/.gitignore index 4a8755b956..6437be5e38 100644 --- a/selfdrive/loggerd/.gitignore +++ b/selfdrive/loggerd/.gitignore @@ -1,2 +1,3 @@ loggerd +encoderd tests/test_logger diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 92cc37a5fb..1efa99298b 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -1,15 +1,13 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon') - +Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc') libs = [common, cereal, messaging, visionipc, 'zmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'bz2', 'OpenCL', 'pthread'] -src = ['logger.cc', 'loggerd.cc', 'video_writer.cc'] +src = ['logger.cc', 'loggerd.cc', 'video_writer.cc', 'remote_encoder.cc'] if arch == "larch64": - src += ['omx_encoder.cc'] - libs += ['OmxCore', 'gsl', 'CB'] + gpucommon + src += ['v4l_encoder.cc'] else: src += ['raw_logger.cc'] @@ -22,6 +20,8 @@ logger_lib = env.Library('logger', src) libs.insert(0, logger_lib) env.Program('loggerd', ['main.cc'], LIBS=libs) +if arch == "larch64": + env.Program('encoderd', ['encoderd.cc'], LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): diff --git a/selfdrive/loggerd/encoder.h b/selfdrive/loggerd/encoder.h index 3d9f957d9f..0a5afa007c 100644 --- a/selfdrive/loggerd/encoder.h +++ b/selfdrive/loggerd/encoder.h @@ -1,13 +1,13 @@ #pragma once #include -#include "selfdrive/loggerd/loggerd.h" +#include "cereal/visionipc/visionipc.h" class VideoEncoder { public: virtual ~VideoEncoder() {} virtual int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) = 0; + int in_width, int in_height, VisionIpcBufExtra *extra) = 0; virtual void encoder_open(const char* path) = 0; virtual void encoder_close() = 0; }; diff --git a/selfdrive/loggerd/encoderd.cc b/selfdrive/loggerd/encoderd.cc new file mode 100644 index 0000000000..ac57d3eea5 --- /dev/null +++ b/selfdrive/loggerd/encoderd.cc @@ -0,0 +1,145 @@ +#include "selfdrive/loggerd/loggerd.h" + +ExitHandler do_exit; + +struct EncoderdState { + int max_waiting = 0; + + // Sync logic for startup + std::atomic encoders_ready = 0; + std::atomic start_frame_id = 0; + bool camera_ready[WideRoadCam + 1] = {}; + bool camera_synced[WideRoadCam + 1] = {}; +}; + +// Handle initial encoder syncing by waiting for all encoders to reach the same frame id +bool sync_encoders(EncoderdState *s, CameraType cam_type, uint32_t frame_id) { + if (s->camera_synced[cam_type]) return true; + + if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { + // add a small margin to the start frame id in case one of the encoders already dropped the next frame + update_max_atomic(s->start_frame_id, frame_id + 2); + if (std::exchange(s->camera_ready[cam_type], true) == false) { + ++s->encoders_ready; + LOGD("camera %d encoder ready", cam_type); + } + return false; + } else { + if (s->max_waiting == 1) update_max_atomic(s->start_frame_id, frame_id); + bool synced = frame_id >= s->start_frame_id; + s->camera_synced[cam_type] = synced; + if (!synced) LOGD("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); + return synced; + } +} + + +void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { + util::set_thread_name(cam_info.filename); + + std::vector encoders; + VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); + + int cur_seg = 0; + while (!do_exit) { + if (!vipc_client.connect(false)) { + util::sleep_for(5); + continue; + } + + // init encoders + if (encoders.empty()) { + VisionBuf buf_info = vipc_client.buffers[0]; + LOGD("encoder init %dx%d", buf_info.width, buf_info.height); + + // main encoder + encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, + cam_info.fps, cam_info.bitrate, cam_info.is_h265, + buf_info.width, buf_info.height, false)); + // qcamera encoder + if (cam_info.has_qcamera) { + encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, + qcam_info.fps, qcam_info.bitrate, qcam_info.is_h265, + qcam_info.frame_width, qcam_info.frame_height, false)); + } + } + + for (int i = 0; i < encoders.size(); ++i) { + encoders[i]->encoder_open(NULL); + } + + bool lagging = false; + while (!do_exit) { + VisionIpcBufExtra extra; + VisionBuf* buf = vipc_client.recv(&extra); + if (buf == nullptr) continue; + + // detect loop around and drop the frames + if (buf->get_frame_id() != extra.frame_id) { + if (!lagging) { + LOGE("encoder %s lag buffer id: %d extra id: %d", cam_info.filename, buf->get_frame_id(), extra.frame_id); + lagging = true; + } + continue; + } + lagging = false; + + if (cam_info.trigger_rotate) { + if (!sync_encoders(s, cam_info.type, extra.frame_id)) { + continue; + } + if (do_exit) break; + } + + // encode a frame + for (int i = 0; i < encoders.size(); ++i) { + int out_id = encoders[i]->encode_frame(buf->y, buf->u, buf->v, + buf->width, buf->height, &extra); + + if (out_id == -1) { + LOGE("Failed to encode frame. frame_id: %d", extra.frame_id); + } + } + + const int frames_per_seg = SEGMENT_LENGTH * MAIN_FPS; + if (cur_seg >= 0 && extra.frame_id >= ((cur_seg + 1) * frames_per_seg) + s->start_frame_id) { + for (auto &e : encoders) { + e->encoder_close(); + e->encoder_open(NULL); + } + ++cur_seg; + } + } + } + + LOG("encoder destroy"); + for(auto &e : encoders) { + e->encoder_close(); + delete e; + } +} + +void encoderd_thread() { + EncoderdState s; + + std::vector encoder_threads; + for (const auto &cam : cameras_logged) { + if (cam.enable) { + encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); + if (cam.trigger_rotate) s.max_waiting++; + } + } + for (auto &t : encoder_threads) t.join(); +} + +int main() { + if (Hardware::TICI()) { + int ret; + ret = util::set_realtime_priority(52); + assert(ret == 0); + ret = util::set_core_affinity({7}); + assert(ret == 0); + } + encoderd_thread(); + return 0; +} diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index a2c2b45a2b..e6bc4fcfa5 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -1,4 +1,6 @@ #include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/remote_encoder.h" +bool USE_REMOTE_ENCODER = false; ExitHandler do_exit; @@ -107,7 +109,7 @@ void encoder_thread(LoggerdState *s, const LogCameraInfo &cam_info) { // encode a frame for (int i = 0; i < encoders.size(); ++i) { int out_id = encoders[i]->encode_frame(buf->y, buf->u, buf->v, - buf->width, buf->height, extra.timestamp_eof); + buf->width, buf->height, &extra); if (out_id == -1) { LOGE("Failed to encode frame. frame_id: %d encode_id: %d", extra.frame_id, encode_idx); @@ -188,15 +190,18 @@ void loggerd_thread() { typedef struct QlogState { std::string name; int counter, freq; + bool encoder; } QlogState; std::unordered_map qlog_states; + std::unordered_map remote_encoders; std::unique_ptr ctx(Context::create()); std::unique_ptr poller(Poller::create()); // subscribe to all socks for (const auto& it : services) { - if (!it.should_log) continue; + const bool encoder = USE_REMOTE_ENCODER & (strcmp(it.name+strlen(it.name)-strlen("EncodeData"), "EncodeData") == 0); + if (!it.should_log && !encoder) continue; LOGD("logging %s (on port %d)", it.name, it.port); SubSocket * sock = SubSocket::create(ctx.get(), it.name); @@ -206,6 +211,7 @@ void loggerd_thread() { .name = it.name, .counter = 0, .freq = it.decimation, + .encoder = encoder, }; } @@ -238,9 +244,14 @@ void loggerd_thread() { Message *msg = nullptr; while (!do_exit && (msg = sock->receive(true))) { const bool in_qlog = qs.freq != -1 && (qs.counter++ % qs.freq == 0); - logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); - bytes_count += msg->getSize(); - delete msg; + + if (qs.encoder) { + bytes_count += handle_encoder_msg(&s, msg, qs.name, remote_encoders[sock]); + } else { + logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); + bytes_count += msg->getSize(); + delete msg; + } rotate_if_needed(&s); diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 761ff5507a..ec014649a8 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -25,8 +25,8 @@ #include "selfdrive/loggerd/encoder.h" #include "selfdrive/loggerd/logger.h" #ifdef QCOM2 -#include "selfdrive/loggerd/omx_encoder.h" -#define Encoder OmxEncoder +#include "selfdrive/loggerd/v4l_encoder.h" +#define Encoder V4LEncoder #else #include "selfdrive/loggerd/raw_logger.h" #define Encoder RawLogger @@ -67,6 +67,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = true, .record = true, + .frame_width = 1928, + .frame_height = 1208, }, { .type = DriverCam, @@ -79,6 +81,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = true, .record = Params().getBool("RecordFront"), + .frame_width = 1928, + .frame_height = 1208, }, { .type = WideRoadCam, @@ -91,6 +95,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = Hardware::TICI(), .record = Hardware::TICI(), + .frame_width = 1928, + .frame_height = 1208, }, }; const LogCameraInfo qcam_info = { @@ -98,6 +104,8 @@ const LogCameraInfo qcam_info = { .fps = MAIN_FPS, .bitrate = 256000, .is_h265 = false, + .enable = true, + .record = true, .frame_width = Hardware::TICI() ? 526 : 480, .frame_height = Hardware::TICI() ? 330 : 360 // keep pixel count the same? }; diff --git a/selfdrive/loggerd/omx_encoder.cc b/selfdrive/loggerd/omx_encoder.cc deleted file mode 100644 index 31e035955a..0000000000 --- a/selfdrive/loggerd/omx_encoder.cc +++ /dev/null @@ -1,547 +0,0 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - -#include "selfdrive/loggerd/omx_encoder.h" -#include "cereal/messaging/messaging.h" - -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include "libyuv.h" - -#include "selfdrive/common/swaglog.h" -#include "selfdrive/common/util.h" -#include "selfdrive/loggerd/include/msm_media_info.h" - -// Check the OMX error code and assert if an error occurred. -#define OMX_CHECK(_expr) \ - do { \ - assert(OMX_ErrorNone == (_expr)); \ - } while (0) - -extern ExitHandler do_exit; - -// ***** OMX callback functions ***** - -void OmxEncoder::wait_for_state(OMX_STATETYPE state_) { - std::unique_lock lk(this->state_lock); - while (this->state != state_) { - this->state_cv.wait(lk); - } -} - -static OMX_CALLBACKTYPE omx_callbacks = { - .EventHandler = OmxEncoder::event_handler, - .EmptyBufferDone = OmxEncoder::empty_buffer_done, - .FillBufferDone = OmxEncoder::fill_buffer_done, -}; - -OMX_ERRORTYPE OmxEncoder::event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data) { - OmxEncoder *e = (OmxEncoder*)app_data; - if (event == OMX_EventCmdComplete) { - assert(data1 == OMX_CommandStateSet); - LOG("set state event 0x%x", data2); - { - std::unique_lock lk(e->state_lock); - e->state = (OMX_STATETYPE)data2; - } - e->state_cv.notify_all(); - } else if (event == OMX_EventError) { - LOGE("OMX error 0x%08x", data1); - } else { - LOGE("OMX unhandled event %d", event); - assert(false); - } - - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->free_in.push(buffer); - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->done_out.push(buffer); - return OMX_ErrorNone; -} - -#define PORT_INDEX_IN 0 -#define PORT_INDEX_OUT 1 - -static const char* omx_color_fomat_name(uint32_t format) __attribute__((unused)); -static const char* omx_color_fomat_name(uint32_t format) { - switch (format) { - case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused"; - case OMX_COLOR_FormatMonochrome: return "OMX_COLOR_FormatMonochrome"; - case OMX_COLOR_Format8bitRGB332: return "OMX_COLOR_Format8bitRGB332"; - case OMX_COLOR_Format12bitRGB444: return "OMX_COLOR_Format12bitRGB444"; - case OMX_COLOR_Format16bitARGB4444: return "OMX_COLOR_Format16bitARGB4444"; - case OMX_COLOR_Format16bitARGB1555: return "OMX_COLOR_Format16bitARGB1555"; - case OMX_COLOR_Format16bitRGB565: return "OMX_COLOR_Format16bitRGB565"; - case OMX_COLOR_Format16bitBGR565: return "OMX_COLOR_Format16bitBGR565"; - case OMX_COLOR_Format18bitRGB666: return "OMX_COLOR_Format18bitRGB666"; - case OMX_COLOR_Format18bitARGB1665: return "OMX_COLOR_Format18bitARGB1665"; - case OMX_COLOR_Format19bitARGB1666: return "OMX_COLOR_Format19bitARGB1666"; - case OMX_COLOR_Format24bitRGB888: return "OMX_COLOR_Format24bitRGB888"; - case OMX_COLOR_Format24bitBGR888: return "OMX_COLOR_Format24bitBGR888"; - case OMX_COLOR_Format24bitARGB1887: return "OMX_COLOR_Format24bitARGB1887"; - case OMX_COLOR_Format25bitARGB1888: return "OMX_COLOR_Format25bitARGB1888"; - case OMX_COLOR_Format32bitBGRA8888: return "OMX_COLOR_Format32bitBGRA8888"; - case OMX_COLOR_Format32bitARGB8888: return "OMX_COLOR_Format32bitARGB8888"; - case OMX_COLOR_FormatYUV411Planar: return "OMX_COLOR_FormatYUV411Planar"; - case OMX_COLOR_FormatYUV411PackedPlanar: return "OMX_COLOR_FormatYUV411PackedPlanar"; - case OMX_COLOR_FormatYUV420Planar: return "OMX_COLOR_FormatYUV420Planar"; - case OMX_COLOR_FormatYUV420PackedPlanar: return "OMX_COLOR_FormatYUV420PackedPlanar"; - case OMX_COLOR_FormatYUV420SemiPlanar: return "OMX_COLOR_FormatYUV420SemiPlanar"; - case OMX_COLOR_FormatYUV422Planar: return "OMX_COLOR_FormatYUV422Planar"; - case OMX_COLOR_FormatYUV422PackedPlanar: return "OMX_COLOR_FormatYUV422PackedPlanar"; - case OMX_COLOR_FormatYUV422SemiPlanar: return "OMX_COLOR_FormatYUV422SemiPlanar"; - case OMX_COLOR_FormatYCbYCr: return "OMX_COLOR_FormatYCbYCr"; - case OMX_COLOR_FormatYCrYCb: return "OMX_COLOR_FormatYCrYCb"; - case OMX_COLOR_FormatCbYCrY: return "OMX_COLOR_FormatCbYCrY"; - case OMX_COLOR_FormatCrYCbY: return "OMX_COLOR_FormatCrYCbY"; - case OMX_COLOR_FormatYUV444Interleaved: return "OMX_COLOR_FormatYUV444Interleaved"; - case OMX_COLOR_FormatRawBayer8bit: return "OMX_COLOR_FormatRawBayer8bit"; - case OMX_COLOR_FormatRawBayer10bit: return "OMX_COLOR_FormatRawBayer10bit"; - case OMX_COLOR_FormatRawBayer8bitcompressed: return "OMX_COLOR_FormatRawBayer8bitcompressed"; - case OMX_COLOR_FormatL2: return "OMX_COLOR_FormatL2"; - case OMX_COLOR_FormatL4: return "OMX_COLOR_FormatL4"; - case OMX_COLOR_FormatL8: return "OMX_COLOR_FormatL8"; - case OMX_COLOR_FormatL16: return "OMX_COLOR_FormatL16"; - case OMX_COLOR_FormatL24: return "OMX_COLOR_FormatL24"; - case OMX_COLOR_FormatL32: return "OMX_COLOR_FormatL32"; - case OMX_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_COLOR_FormatYUV422PackedSemiPlanar: return "OMX_COLOR_FormatYUV422PackedSemiPlanar"; - case OMX_COLOR_Format18BitBGR666: return "OMX_COLOR_Format18BitBGR666"; - case OMX_COLOR_Format24BitARGB6666: return "OMX_COLOR_Format24BitARGB6666"; - case OMX_COLOR_Format24BitABGR6666: return "OMX_COLOR_Format24BitABGR6666"; - - case OMX_COLOR_FormatAndroidOpaque: return "OMX_COLOR_FormatAndroidOpaque"; - case OMX_TI_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_TI_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_QCOM_COLOR_FormatYVU420SemiPlanar: return "OMX_QCOM_COLOR_FormatYVU420SemiPlanar"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka"; - case OMX_SEC_COLOR_FormatNV12Tiled: return "OMX_SEC_COLOR_FormatNV12Tiled"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m"; - - // case QOMX_COLOR_FormatYVU420SemiPlanar: return "QOMX_COLOR_FormatYVU420SemiPlanar"; - case QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka: return "QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka"; - case QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka"; - // case QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka"; - // case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed"; - case QOMX_COLOR_Format32bitRGBA8888: return "QOMX_COLOR_Format32bitRGBA8888"; - case QOMX_COLOR_Format32bitRGBA8888Compressed: return "QOMX_COLOR_Format32bitRGBA8888Compressed"; - - default: - return "unkn"; - } -} - - -// ***** encoder functions ***** -OmxEncoder::OmxEncoder(const char* filename, CameraType type, int in_width, int in_height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write) - : in_width_(in_width), in_height_(in_height), width(out_width), height(out_height) { - this->filename = filename; - this->type = type; - this->write = write; - this->fps = fps; - this->remuxing = !h265; - - this->downscale = in_width != out_width || in_height != out_height; - if (this->downscale) { - this->y_ptr2 = (uint8_t *)malloc(this->width*this->height); - this->u_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - this->v_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - } - - auto component = (OMX_STRING)(h265 ? "OMX.qcom.video.encoder.hevc" : "OMX.qcom.video.encoder.avc"); - int err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks); - if (err != OMX_ErrorNone) { - LOGE("error getting codec: %x", err); - } - assert(err == OMX_ErrorNone); - // printf("handle: %p\n", this->handle); - - // setup input port - - OMX_PARAM_PORTDEFINITIONTYPE in_port = {0}; - in_port.nSize = sizeof(in_port); - in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - - in_port.format.video.nFrameWidth = this->width; - in_port.format.video.nFrameHeight = this->height; - in_port.format.video.nStride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - in_port.format.video.nSliceHeight = this->height; - // in_port.nBufferSize = (this->width * this->height * 3) / 2; - in_port.nBufferSize = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_port.format.video.xFramerate = (this->fps * 65536); - in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused; - // in_port.format.video.eColorFormat = OMX_COLOR_FormatYUV420SemiPlanar; - in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - this->in_buf_headers.resize(in_port.nBufferCountActual); - - // setup output port - - OMX_PARAM_PORTDEFINITIONTYPE out_port = {0}; - out_port.nSize = sizeof(out_port); - out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port)); - out_port.format.video.nFrameWidth = this->width; - out_port.format.video.nFrameHeight = this->height; - out_port.format.video.xFramerate = 0; - out_port.format.video.nBitrate = bitrate; - if (h265) { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingHEVC; - } else { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingAVC; - } - out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - this->out_buf_headers.resize(out_port.nBufferCountActual); - - OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0}; - bitrate_type.nSize = sizeof(bitrate_type); - bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - bitrate_type.eControlRate = OMX_Video_ControlRateVariable; - bitrate_type.nTargetBitrate = bitrate; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - - if (h265) { - // setup HEVC - OMX_VIDEO_PARAM_PROFILELEVELTYPE hevc_type = {0}; - OMX_INDEXTYPE index_type = OMX_IndexParamVideoProfileLevelCurrent; - hevc_type.nSize = sizeof(hevc_type); - hevc_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - - hevc_type.eProfile = OMX_VIDEO_HEVCProfileMain; - hevc_type.eLevel = OMX_VIDEO_HEVCHighTierLevel5; - - OMX_CHECK(OMX_SetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - } else { - // setup h264 - OMX_VIDEO_PARAM_AVCTYPE avc = { 0 }; - avc.nSize = sizeof(avc); - avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - - avc.nBFrames = 0; - avc.nPFrames = 15; - - avc.eProfile = OMX_VIDEO_AVCProfileHigh; - avc.eLevel = OMX_VIDEO_AVCLevel31; - - avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB; - avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable; - - avc.nRefFrames = 1; - avc.bUseHadamard = OMX_TRUE; - avc.bEntropyCodingCABAC = OMX_TRUE; - avc.bWeightedPPrediction = OMX_TRUE; - avc.bconstIpred = OMX_TRUE; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - } - - - // for (int i = 0; ; i++) { - // OMX_VIDEO_PARAM_PORTFORMATTYPE video_port_format = {0}; - // video_port_format.nSize = sizeof(video_port_format); - // video_port_format.nIndex = i; - // video_port_format.nPortIndex = PORT_INDEX_IN; - // if (OMX_GetParameter(this->handle, OMX_IndexParamVideoPortFormat, &video_port_format) != OMX_ErrorNone) - // break; - // printf("in %d: compression 0x%x format 0x%x %s\n", i, - // video_port_format.eCompressionFormat, video_port_format.eColorFormat, - // omx_color_fomat_name(video_port_format.eColorFormat)); - // } - - // for (int i=0; i<32; i++) { - // OMX_VIDEO_PARAM_PROFILELEVELTYPE params = {0}; - // params.nSize = sizeof(params); - // params.nPortIndex = PORT_INDEX_OUT; - // params.nProfileIndex = i; - // if (OMX_GetParameter(this->handle, OMX_IndexParamVideoProfileLevelQuerySupported, ¶ms) != OMX_ErrorNone) - // break; - // printf("profile %d level 0x%x\n", params.eProfile, params.eLevel); - // } - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_IN, this, - in_port.nBufferSize)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_OUT, this, - out_port.nBufferSize)); - } - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL)); - - wait_for_state(OMX_StateExecuting); - - // give omx all the output buffers - for (auto &buf : this->out_buf_headers) { - // printf("fill %p\n", this->out_buf_headers[i]); - OMX_CHECK(OMX_FillThisBuffer(this->handle, buf)); - } - - // fill the input free queue - for (auto &buf : this->in_buf_headers) { - this->free_in.push(buf); - } - - LOGE("omx initialized - in: %d - out %d", this->in_buf_headers.size(), this->out_buf_headers.size()); - - service_name = this->type == DriverCam ? "driverEncodeData" : - (this->type == WideRoadCam ? "wideRoadEncodeData" : - (this->remuxing ? "qRoadEncodeData" : "roadEncodeData")); - pm.reset(new PubMaster({service_name})); -} - -void OmxEncoder::callback_handler(OmxEncoder *e) { - // OMX documentation specifies to not empty the buffer from the callback function - // so we use this intermediate handler to copy the buffer for further writing - // and give it back to OMX. We could also send the data over msgq from here. - bool exit = false; - - while (!exit) { - OMX_BUFFERHEADERTYPE *buffer = e->done_out.pop(); - OmxBuffer *new_buffer = (OmxBuffer*)malloc(sizeof(OmxBuffer) + buffer->nFilledLen); - assert(new_buffer); - - new_buffer->header = *buffer; - memcpy(new_buffer->data, buffer->pBuffer + buffer->nOffset, buffer->nFilledLen); - - e->to_write.push(new_buffer); - -#ifdef QCOM2 - if (buffer->nFlags & OMX_BUFFERFLAG_CODECCONFIG) { - buffer->nTimeStamp = 0; - } - - if (buffer->nFlags & OMX_BUFFERFLAG_EOS) { - buffer->nTimeStamp = 0; - } -#endif - - if (buffer->nFlags & OMX_BUFFERFLAG_EOS) { - exit = true; - } - - // give omx back the buffer - // TOOD: fails when shutting down - OMX_CHECK(OMX_FillThisBuffer(e->handle, buffer)); - } -} - -void OmxEncoder::write_and_broadcast_handler(OmxEncoder *e){ - bool exit = false; - - e->segment_num++; - uint32_t idx = 0; - while (!exit) { - OmxBuffer *out_buf = e->to_write.pop(); - - MessageBuilder msg; - auto edata = (e->type == DriverCam) ? msg.initEvent(true).initDriverEncodeData() : - ((e->type == WideRoadCam) ? msg.initEvent(true).initWideRoadEncodeData() : - (e->remuxing ? msg.initEvent(true).initQRoadEncodeData() : msg.initEvent(true).initRoadEncodeData())); - edata.setData(kj::heapArray(out_buf->data, out_buf->header.nFilledLen)); - edata.setTimestampEof(out_buf->header.nTimeStamp); - edata.setIdx(idx++); - edata.setSegmentNum(e->segment_num); - edata.setFlags(out_buf->header.nFlags); - e->pm->send(e->service_name, msg); - - OmxEncoder::handle_out_buf(e, out_buf); - if (out_buf->header.nFlags & OMX_BUFFERFLAG_EOS) { - exit = true; - } - - free(out_buf); - } -} - - -void OmxEncoder::handle_out_buf(OmxEncoder *e, OmxBuffer *out_buf) { - if (!(out_buf->header.nFlags & OMX_BUFFERFLAG_EOS) && e->writer) { - e->writer->write(out_buf->data, - out_buf->header.nFilledLen, - out_buf->header.nTimeStamp, - out_buf->header.nFlags & OMX_BUFFERFLAG_CODECCONFIG, - out_buf->header.nFlags & OMX_BUFFERFLAG_SYNCFRAME); - } -} - -int OmxEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) { - assert(in_width == this->in_width_); - assert(in_height == this->in_height_); - int err; - if (!this->is_open) { - return -1; - } - - // this sometimes freezes... put it outside the encoder lock so we can still trigger rotates... - // THIS IS A REALLY BAD IDEA, but apparently the race has to happen 30 times to trigger this - //pthread_mutex_unlock(&this->lock); - OMX_BUFFERHEADERTYPE* in_buf = nullptr; - while (!this->free_in.try_pop(in_buf, 20)) { - if (do_exit) { - return -1; - } - } - - //pthread_mutex_lock(&this->lock); - - int ret = this->counter; - - uint8_t *in_buf_ptr = in_buf->pBuffer; - // printf("in_buf ptr %p\n", in_buf_ptr); - - uint8_t *in_y_ptr = in_buf_ptr; - int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, this->width); - // uint8_t *in_uv_ptr = in_buf_ptr + (this->width * this->height); - uint8_t *in_uv_ptr = in_buf_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, this->height)); - - if (this->downscale) { - I420Scale(y_ptr, in_width, - u_ptr, in_width/2, - v_ptr, in_width/2, - in_width, in_height, - this->y_ptr2, this->width, - this->u_ptr2, this->width/2, - this->v_ptr2, this->width/2, - this->width, this->height, - libyuv::kFilterNone); - y_ptr = this->y_ptr2; - u_ptr = this->u_ptr2; - v_ptr = this->v_ptr2; - } - err = libyuv::I420ToNV12(y_ptr, this->width, - u_ptr, this->width/2, - v_ptr, this->width/2, - in_y_ptr, in_y_stride, - in_uv_ptr, in_uv_stride, - this->width, this->height); - assert(err == 0); - - // in_buf->nFilledLen = (this->width*this->height) + (this->width*this->height/2); - in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME; - in_buf->nOffset = 0; - in_buf->nTimeStamp = ts/1000LL; // OMX_TICKS, in microseconds - this->last_t = in_buf->nTimeStamp; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - this->dirty = true; - - this->counter++; - - return ret; -} - -void OmxEncoder::encoder_open(const char* path) { - if (this->write) { - writer.reset(new VideoWriter(path, this->filename, this->remuxing, this->width, this->height, this->fps, !this->remuxing, false)); - } - - // start writer threads - callback_handler_thread = std::thread(OmxEncoder::callback_handler, this); - write_handler_thread = std::thread(OmxEncoder::write_and_broadcast_handler, this); - - this->is_open = true; - this->counter = 0; -} - -void OmxEncoder::encoder_close() { - if (this->is_open) { - if (this->dirty) { - // drain output only if there could be frames in the encoder - - OMX_BUFFERHEADERTYPE* in_buf = this->free_in.pop(); - in_buf->nFilledLen = 0; - in_buf->nOffset = 0; - in_buf->nFlags = OMX_BUFFERFLAG_EOS; - in_buf->nTimeStamp = this->last_t + 1000000LL/this->fps; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - this->dirty = false; - } - - callback_handler_thread.join(); - write_handler_thread.join(); - - writer.reset(); - } - this->is_open = false; -} - -OmxEncoder::~OmxEncoder() { - assert(!this->is_open); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_IN, buf)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, buf)); - } - - wait_for_state(OMX_StateLoaded); - - OMX_CHECK(OMX_FreeHandle(this->handle)); - - OMX_BUFFERHEADERTYPE *buf; - while (this->free_in.try_pop(buf)); - while (this->done_out.try_pop(buf)); - - OmxBuffer *write_buf; - while (this->to_write.try_pop(write_buf)) { - free(write_buf); - }; - - if (this->downscale) { - free(this->y_ptr2); - free(this->u_ptr2); - free(this->v_ptr2); - } -} diff --git a/selfdrive/loggerd/omx_encoder.h b/selfdrive/loggerd/omx_encoder.h deleted file mode 100644 index e57dccbe11..0000000000 --- a/selfdrive/loggerd/omx_encoder.h +++ /dev/null @@ -1,79 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include - -#include "selfdrive/common/queue.h" -#include "selfdrive/loggerd/encoder.h" -#include "selfdrive/loggerd/video_writer.h" - -struct OmxBuffer { - OMX_BUFFERHEADERTYPE header; - OMX_U8 data[]; -}; - - -// OmxEncoder, lossey codec using hardware hevc -class OmxEncoder : public VideoEncoder { -public: - OmxEncoder(const char* filename, CameraType type, int width, int height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write = true); - ~OmxEncoder(); - int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts); - void encoder_open(const char* path); - void encoder_close(); - - // OMX callbacks - static OMX_ERRORTYPE event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data); - static OMX_ERRORTYPE empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - static OMX_ERRORTYPE fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - -private: - void wait_for_state(OMX_STATETYPE state); - static void callback_handler(OmxEncoder *e); - static void write_and_broadcast_handler(OmxEncoder *e); - static void handle_out_buf(OmxEncoder *e, OmxBuffer *out_buf); - - int in_width_, in_height_; - int width, height, fps; - bool is_open = false; - bool dirty = false; - bool write = false; - int counter = 0; - std::thread callback_handler_thread; - std::thread write_handler_thread; - int segment_num = -1; - std::unique_ptr pm; - const char *service_name; - - const char* filename; - CameraType type; - - std::mutex state_lock; - std::condition_variable state_cv; - OMX_STATETYPE state = OMX_StateLoaded; - - OMX_HANDLETYPE handle; - - std::vector in_buf_headers; - std::vector out_buf_headers; - - uint64_t last_t; - - SafeQueue free_in; - SafeQueue done_out; - SafeQueue to_write; - - bool remuxing; - std::unique_ptr writer; - - bool downscale; - uint8_t *y_ptr2, *u_ptr2, *v_ptr2; -}; diff --git a/selfdrive/loggerd/raw_logger.cc b/selfdrive/loggerd/raw_logger.cc index 29d421a881..72c8d0d93e 100644 --- a/selfdrive/loggerd/raw_logger.cc +++ b/selfdrive/loggerd/raw_logger.cc @@ -59,7 +59,7 @@ void RawLogger::encoder_close() { } int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) { + int in_width, int in_height, VisionIpcBufExtra *extra) { assert(in_width == this->in_width_); assert(in_height == this->in_height_); diff --git a/selfdrive/loggerd/raw_logger.h b/selfdrive/loggerd/raw_logger.h index 56bd08ff1f..14c4a61ea0 100644 --- a/selfdrive/loggerd/raw_logger.h +++ b/selfdrive/loggerd/raw_logger.h @@ -12,6 +12,7 @@ extern "C" { } #include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/loggerd.h" #include "selfdrive/loggerd/video_writer.h" class RawLogger : public VideoEncoder { @@ -20,7 +21,7 @@ class RawLogger : public VideoEncoder { int bitrate, bool h265, int out_width, int out_height, bool write = true); ~RawLogger(); int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts); + int in_width, int in_height, VisionIpcBufExtra *extra); void encoder_open(const char* path); void encoder_close(); diff --git a/selfdrive/loggerd/remote_encoder.cc b/selfdrive/loggerd/remote_encoder.cc new file mode 100644 index 0000000000..c79595b0fe --- /dev/null +++ b/selfdrive/loggerd/remote_encoder.cc @@ -0,0 +1,84 @@ +#include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/remote_encoder.h" + +int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct RemoteEncoder &re) { + const LogCameraInfo &cam_info = (name == "driverEncodeData") ? cameras_logged[1] : + ((name == "wideRoadEncodeData") ? cameras_logged[2] : + ((name == "qRoadEncodeData") ? qcam_info : cameras_logged[0])); + if (!cam_info.record) return 0; // TODO: handle this by not subscribing + + int bytes_count = 0; + + // TODO: AlignedBuffer is making a copy and allocing + //AlignedBuffer aligned_buf; + //capnp::FlatArrayMessageReader cmsg(aligned_buf.align(msg->getData(), msg->getSize())); + capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize())); + auto event = cmsg.getRoot(); + auto edata = (name == "driverEncodeData") ? event.getDriverEncodeData() : + ((name == "wideRoadEncodeData") ? event.getWideRoadEncodeData() : + ((name == "qRoadEncodeData") ? event.getQRoadEncodeData() : event.getRoadEncodeData())); + auto idx = edata.getIdx(); + auto flags = idx.getFlags(); + + // rotation happened, process the queue (happens before the current message) + if (re.logger_segment != s->rotate_segment) { + re.logger_segment = s->rotate_segment; + for (auto &qmsg: re.q) { + bytes_count += handle_encoder_msg(s, qmsg, name, re); + } + re.q.clear(); + } + + if (!re.writer) { + // only create on iframe + if (flags & V4L2_BUF_FLAG_KEYFRAME) { + if (re.dropped_frames) { + // this should only happen for the first segment, maybe + LOGD("%s: dropped %d non iframe packets before init", name.c_str(), re.dropped_frames); + re.dropped_frames = 0; + } + re.writer.reset(new VideoWriter(s->segment_path, + cam_info.filename, !cam_info.is_h265, + cam_info.frame_width, cam_info.frame_height, + cam_info.fps, cam_info.is_h265, false)); + // write the header + auto header = edata.getHeader(); + re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); + re.segment = idx.getSegmentNum(); + } else { + ++re.dropped_frames; + return bytes_count; + } + } + + if (re.segment != idx.getSegmentNum()) { + if (re.writer) { + // encoder is on the next segment, this segment is over so we close the videowriter + re.writer.reset(); + ++s->ready_to_rotate; + LOGD("rotate %d -> %d ready %d/%d", re.segment, idx.getSegmentNum(), s->ready_to_rotate.load(), s->max_waiting); + } + // queue up all the new segment messages, they go in after the rotate + re.q.push_back(msg); + } else { + auto data = edata.getData(); + re.writer->write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); + + // put it in log stream as the idx packet + MessageBuilder bmsg; + auto evt = bmsg.initEvent(event.getValid()); + evt.setLogMonoTime(event.getLogMonoTime()); + if (name == "driverEncodeData") { evt.setDriverEncodeIdx(idx); } + if (name == "wideRoadEncodeData") { evt.setWideRoadEncodeIdx(idx); } + if (name == "qRoadEncodeData") { evt.setQRoadEncodeIdx(idx); } + if (name == "roadEncodeData") { evt.setRoadEncodeIdx(idx); } + auto new_msg = bmsg.toBytes(); + logger_log(&s->logger, (uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? + delete msg; + bytes_count += new_msg.size(); + } + + return bytes_count; +} + + diff --git a/selfdrive/loggerd/remote_encoder.h b/selfdrive/loggerd/remote_encoder.h new file mode 100644 index 0000000000..6fc91a2209 --- /dev/null +++ b/selfdrive/loggerd/remote_encoder.h @@ -0,0 +1,12 @@ +#include "selfdrive/loggerd/video_writer.h" +#define V4L2_BUF_FLAG_KEYFRAME 0x00000008 + +struct RemoteEncoder { + std::unique_ptr writer; + int segment = -1; + std::vector q; + int logger_segment = -1; + int dropped_frames = 0; +}; + +int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct RemoteEncoder &re); \ No newline at end of file diff --git a/selfdrive/loggerd/tests/test_encoder.py b/selfdrive/loggerd/tests/test_encoder.py index 9479b6256a..760c255443 100755 --- a/selfdrive/loggerd/tests/test_encoder.py +++ b/selfdrive/loggerd/tests/test_encoder.py @@ -107,7 +107,8 @@ class TestEncoder(unittest.TestCase): # sanity check file size file_size = os.path.getsize(file_path) - self.assertTrue(math.isclose(file_size, size, rel_tol=FILE_SIZE_TOLERANCE)) + self.assertTrue(math.isclose(file_size, size, rel_tol=FILE_SIZE_TOLERANCE), + f"{file_path} size {file_size} isn't close to target size {size}") # Check encodeIdx if encode_idx_name is not None: diff --git a/selfdrive/loggerd/v4l_encoder.cc b/selfdrive/loggerd/v4l_encoder.cc new file mode 100644 index 0000000000..b61bf01019 --- /dev/null +++ b/selfdrive/loggerd/v4l_encoder.cc @@ -0,0 +1,401 @@ +#include +#include +#include + +#include "selfdrive/loggerd/v4l_encoder.h" +#include "selfdrive/common/util.h" +#include "selfdrive/common/timing.h" + +#include "libyuv.h" +#include "msm_media_info.h" + +// has to be in this order +#include "v4l2-controls.h" +#include +#define V4L2_QCOM_BUF_FLAG_CODECCONFIG 0x00020000 +#define V4L2_QCOM_BUF_FLAG_EOS 0x02000000 + +// echo 0x7fffffff > /sys/kernel/debug/msm_vidc/debug_level +const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0; + +#define checked_ioctl(x,y,z) { int _ret = HANDLE_EINTR(ioctl(x,y,z)); if (_ret!=0) { LOGE("checked_ioctl failed %d %lx %p", x, y, z); } assert(_ret==0); } + +static void dequeue_buffer(int fd, v4l2_buf_type buf_type, unsigned int *index=NULL, unsigned int *bytesused=NULL, unsigned int *flags=NULL, struct timeval *timestamp=NULL) { + v4l2_plane plane = {0}; + v4l2_buffer v4l_buf = { + .type = buf_type, + .memory = V4L2_MEMORY_USERPTR, + .m = { .planes = &plane, }, + .length = 1, + }; + checked_ioctl(fd, VIDIOC_DQBUF, &v4l_buf); + + if (index) *index = v4l_buf.index; + if (bytesused) *bytesused = v4l_buf.m.planes[0].bytesused; + if (flags) *flags = v4l_buf.flags; + if (timestamp) *timestamp = v4l_buf.timestamp; + assert(v4l_buf.m.planes[0].data_offset == 0); +} + +static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, VisionBuf *buf, struct timeval timestamp={0}) { + v4l2_plane plane = { + .length = (unsigned int)buf->len, + .m = { .userptr = (unsigned long)buf->addr, }, + .reserved = {(unsigned int)buf->fd} + }; + + v4l2_buffer v4l_buf = { + .type = buf_type, + .index = index, + .memory = V4L2_MEMORY_USERPTR, + .m = { .planes = &plane, }, + .length = 1, + .bytesused = 0, + .flags = V4L2_BUF_FLAG_TIMESTAMP_COPY, + .timestamp = timestamp + }; + + checked_ioctl(fd, VIDIOC_QBUF, &v4l_buf); +} + +static void request_buffers(int fd, v4l2_buf_type buf_type, unsigned int count) { + struct v4l2_requestbuffers reqbuf = { + .type = buf_type, + .memory = V4L2_MEMORY_USERPTR, + .count = count + }; + checked_ioctl(fd, VIDIOC_REQBUFS, &reqbuf); +} + +// TODO: writing should be moved to loggerd +void V4LEncoder::write_handler(V4LEncoder *e, const char *path) { + VideoWriter writer(path, e->filename, !e->h265, e->width, e->height, e->fps, e->h265, false); + + bool first = true; + kj::Array* out_buf; + while ((out_buf = e->to_write.pop())) { + capnp::FlatArrayMessageReader cmsg(*out_buf); + cereal::Event::Reader event = cmsg.getRoot(); + + auto edata = (e->type == DriverCam) ? event.getDriverEncodeData() : + ((e->type == WideRoadCam) ? event.getWideRoadEncodeData() : + (e->h265 ? event.getRoadEncodeData() : event.getQRoadEncodeData())); + auto idx = edata.getIdx(); + auto flags = idx.getFlags(); + + if (first) { + assert(flags & V4L2_BUF_FLAG_KEYFRAME); + auto header = edata.getHeader(); + writer.write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); + first = false; + } + + // dangerous cast from const, but should be fine + auto data = edata.getData(); + if (data.size() > 0) { + writer.write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); + } + + // free the data + delete out_buf; + } + + // VideoWriter is freed on out of scope +} + +void V4LEncoder::dequeue_handler(V4LEncoder *e) { + std::string dequeue_thread_name = "dq-"+std::string(e->filename); + util::set_thread_name(dequeue_thread_name.c_str()); + + e->segment_num++; + uint32_t idx = -1; + bool exit = false; + + // POLLIN is capture, POLLOUT is frame + struct pollfd pfd; + pfd.events = POLLIN | POLLOUT; + pfd.fd = e->fd; + + // save the header + kj::Array header; + + while (!exit) { + int rc = poll(&pfd, 1, 1000); + if (!rc) { LOGE("encoder dequeue poll timeout"); continue; } + + if (env_debug_encoder >= 2) { + printf("%20s poll %x at %.2f ms\n", e->filename, pfd.revents, millis_since_boot()); + } + + int frame_id = -1; + if (pfd.revents & POLLIN) { + unsigned int bytesused, flags, index; + struct timeval timestamp; + dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, &index, &bytesused, &flags, ×tamp); + e->buf_out[index].sync(VISIONBUF_SYNC_FROM_DEVICE); + uint8_t *buf = (uint8_t*)e->buf_out[index].addr; + int64_t ts = timestamp.tv_sec * 1000000 + timestamp.tv_usec; + + // eof packet, we exit + if (flags & V4L2_QCOM_BUF_FLAG_EOS) { + if (e->write) e->to_write.push(NULL); + exit = true; + } else if (flags & V4L2_QCOM_BUF_FLAG_CODECCONFIG) { + // save header + header = kj::heapArray(buf, bytesused); + } else { + VisionIpcBufExtra extra = e->extras.pop(); + assert(extra.timestamp_eof/1000 == ts); // stay in sync + + frame_id = extra.frame_id; + ++idx; + + // broadcast packet + MessageBuilder msg; + auto event = msg.initEvent(true); + auto edat = (e->type == DriverCam) ? event.initDriverEncodeData() : + ((e->type == WideRoadCam) ? event.initWideRoadEncodeData() : + (e->h265 ? event.initRoadEncodeData() : event.initQRoadEncodeData())); + auto edata = edat.initIdx(); + edata.setFrameId(extra.frame_id); + edata.setTimestampSof(extra.timestamp_sof); + edata.setTimestampEof(extra.timestamp_eof); + edata.setType(e->h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264); + edata.setEncodeId(idx); + edata.setSegmentNum(e->segment_num); + edata.setSegmentId(idx); + edata.setFlags(flags); + edata.setLen(bytesused); + edat.setData(kj::arrayPtr(buf, bytesused)); + if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); + + auto words = new kj::Array(capnp::messageToFlatArray(msg)); + auto bytes = words->asBytes(); + e->pm->send(e->service_name, bytes.begin(), bytes.size()); + if (e->write) { + e->to_write.push(words); + } else { + delete words; + } + } + + if (env_debug_encoder) { + printf("%20s got(%d) %6d bytes flags %8x idx %4d id %8d ts %ld lat %.2f ms (%lu frames free)\n", + e->filename, index, bytesused, flags, idx, frame_id, ts, millis_since_boot()-(ts/1000.), e->free_buf_in.size()); + } + + // requeue the buffer + queue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, index, &e->buf_out[index]); + } + + if (pfd.revents & POLLOUT) { + unsigned int index; + dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, &index); + e->free_buf_in.push(index); + } + } +} + +V4LEncoder::V4LEncoder( + const char* filename, CameraType type, int in_width, int in_height, + int fps, int bitrate, bool h265, int out_width, int out_height, bool write) + : type(type), in_width_(in_width), in_height_(in_height), + filename(filename), h265(h265), + width(out_width), height(out_height), fps(fps), write(write) { + fd = open("/dev/v4l/by-path/platform-aa00000.qcom_vidc-video-index1", O_RDWR|O_NONBLOCK); + assert(fd >= 0); + + struct v4l2_capability cap; + checked_ioctl(fd, VIDIOC_QUERYCAP, &cap); + LOGD("opened encoder device %s %s = %d", cap.driver, cap.card, fd); + assert(strcmp((const char *)cap.driver, "msm_vidc_driver") == 0); + assert(strcmp((const char *)cap.card, "msm_vidc_venc") == 0); + + struct v4l2_format fmt_out = { + .type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, + .fmt = { + .pix_mp = { + // downscales are free with v4l + .width = (unsigned int)out_width, + .height = (unsigned int)out_height, + .pixelformat = h265 ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, + .field = V4L2_FIELD_ANY, + .colorspace = V4L2_COLORSPACE_DEFAULT, + } + } + }; + checked_ioctl(fd, VIDIOC_S_FMT, &fmt_out); + + v4l2_streamparm streamparm = { + .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, + .parm = { + .output = { + // TODO: more stuff here? we don't know + .timeperframe = { + .numerator = 1, + .denominator = 20 + } + } + } + }; + checked_ioctl(fd, VIDIOC_S_PARM, &streamparm); + + struct v4l2_format fmt_in = { + .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, + .fmt = { + .pix_mp = { + .width = (unsigned int)in_width, + .height = (unsigned int)in_height, + .pixelformat = V4L2_PIX_FMT_NV12, + .field = V4L2_FIELD_ANY, + .colorspace = V4L2_COLORSPACE_470_SYSTEM_BG, + } + } + }; + checked_ioctl(fd, VIDIOC_S_FMT, &fmt_in); + + LOGD("in buffer size %d, out buffer size %d", + fmt_in.fmt.pix_mp.plane_fmt[0].sizeimage, + fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); + + // shared ctrls + { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDEO_HEADER_MODE, .value = V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE}, + { .id = V4L2_CID_MPEG_VIDEO_BITRATE, .value = bitrate}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL, .value = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY, .value = V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD, .value = 1}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } + + if (h265) { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 29}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } else { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 15}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE, .value = 0}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } + + // allocate buffers + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, BUF_OUT_COUNT); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, BUF_IN_COUNT); + + // start encoder + v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); + buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); + + // queue up output buffers + for (unsigned int i = 0; i < BUF_OUT_COUNT; i++) { + buf_out[i].allocate(fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); + queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, i, &buf_out[i]); + } + // queue up input buffers + for (unsigned int i = 0; i < BUF_IN_COUNT; i++) { + buf_in[i].allocate(fmt_in.fmt.pix_mp.plane_fmt[0].sizeimage); + free_buf_in.push(i); + } + + // publish + service_name = this->type == DriverCam ? "driverEncodeData" : + (this->type == WideRoadCam ? "wideRoadEncodeData" : + (this->h265 ? "roadEncodeData" : "qRoadEncodeData")); + pm.reset(new PubMaster({service_name})); +} + + +void V4LEncoder::encoder_open(const char* path) { + dequeue_handler_thread = std::thread(V4LEncoder::dequeue_handler, this); + if (this->write) write_handler_thread = std::thread(V4LEncoder::write_handler, this, path); + this->is_open = true; + this->counter = 0; +} + +int V4LEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width, int in_height, VisionIpcBufExtra *extra) { + assert(in_width == in_width_); + assert(in_height == in_height_); + assert(is_open); + + // reserve buffer + int buffer_in = free_buf_in.pop(); + + uint8_t *in_y_ptr = (uint8_t*)buf_in[buffer_in].addr; + int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, in_width); + int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, in_width); + uint8_t *in_uv_ptr = in_y_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, in_height)); + + // GRRR COPY + int err = libyuv::I420ToNV12(y_ptr, in_width, + u_ptr, in_width/2, + v_ptr, in_width/2, + in_y_ptr, in_y_stride, + in_uv_ptr, in_uv_stride, + in_width, in_height); + assert(err == 0); + + struct timeval timestamp { + .tv_sec = (long)(extra->timestamp_eof/1000000000), + .tv_usec = (long)((extra->timestamp_eof/1000) % 1000000), + }; + + // push buffer + extras.push(*extra); + buf_in[buffer_in].sync(VISIONBUF_SYNC_TO_DEVICE); + queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, buffer_in, &buf_in[buffer_in], timestamp); + + return this->counter++; +} + +void V4LEncoder::encoder_close() { + if (this->is_open) { + // pop all the frames before closing, then put the buffers back + for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.pop(); + for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.push(i); + // no frames, stop the encoder + struct v4l2_encoder_cmd encoder_cmd = { .cmd = V4L2_ENC_CMD_STOP }; + checked_ioctl(fd, VIDIOC_ENCODER_CMD, &encoder_cmd); + // join waits for V4L2_QCOM_BUF_FLAG_EOS + dequeue_handler_thread.join(); + assert(extras.empty()); + if (this->write) write_handler_thread.join(); + assert(to_write.empty()); + } + this->is_open = false; +} + +V4LEncoder::~V4LEncoder() { + encoder_close(); + v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, 0); + buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, 0); + close(fd); +} diff --git a/selfdrive/loggerd/v4l_encoder.h b/selfdrive/loggerd/v4l_encoder.h new file mode 100644 index 0000000000..43b70baebd --- /dev/null +++ b/selfdrive/loggerd/v4l_encoder.h @@ -0,0 +1,48 @@ +#pragma once + +#include "selfdrive/common/queue.h" +#include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/video_writer.h" + +#define BUF_IN_COUNT 7 +#define BUF_OUT_COUNT 6 + +class V4LEncoder : public VideoEncoder { +public: + V4LEncoder(const char* filename, CameraType type, int width, int height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write = true); + ~V4LEncoder(); + int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width, int in_height, VisionIpcBufExtra *extra); + void encoder_open(const char* path); + void encoder_close(); +private: + int fd; + + const char* filename; + CameraType type; + unsigned int in_width_, in_height_; + bool h265; + bool is_open = false; + int segment_num = -1; + int counter = 0; + + std::unique_ptr pm; + const char *service_name; + + static void dequeue_handler(V4LEncoder *e); + std::thread dequeue_handler_thread; + + VisionBuf buf_in[BUF_IN_COUNT]; + VisionBuf buf_out[BUF_OUT_COUNT]; + SafeQueue free_buf_in; + + SafeQueue extras; + + // writing support + int width, height, fps; + bool write; + static void write_handler(V4LEncoder *e, const char *path); + std::thread write_handler_thread; + SafeQueue* > to_write; +}; diff --git a/selfdrive/loggerd/video_writer.cc b/selfdrive/loggerd/video_writer.cc index f9034f6912..51e606dc5c 100644 --- a/selfdrive/loggerd/video_writer.cc +++ b/selfdrive/loggerd/video_writer.cc @@ -48,7 +48,6 @@ VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, int err = avio_open(&this->ofmt_ctx->pb, this->vid_path.c_str(), AVIO_FLAG_WRITE); assert(err >= 0); - this->wrote_codec_config = false; } else { this->of = util::safe_fopen(this->vid_path.c_str(), "wb"); assert(this->of); diff --git a/selfdrive/loggerd/video_writer.h b/selfdrive/loggerd/video_writer.h index 8217b859bf..8048d93a07 100644 --- a/selfdrive/loggerd/video_writer.h +++ b/selfdrive/loggerd/video_writer.h @@ -20,6 +20,4 @@ private: AVFormatContext *ofmt_ctx; AVStream *out_stream; bool remuxing, raw; - - bool wrote_codec_config; }; \ No newline at end of file diff --git a/selfdrive/loggerd/include/msm_media_info.h b/third_party/linux/include/msm_media_info.h similarity index 100% rename from selfdrive/loggerd/include/msm_media_info.h rename to third_party/linux/include/msm_media_info.h diff --git a/third_party/linux/include/v4l2-controls.h b/third_party/linux/include/v4l2-controls.h new file mode 100644 index 0000000000..d14cd8fabe --- /dev/null +++ b/third_party/linux/include/v4l2-controls.h @@ -0,0 +1,1696 @@ +/* + * Video for Linux Two controls header file + * + * Copyright (C) 1999-2012 the contributors + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * Alternatively you can redistribute this file under the terms of the + * BSD license as stated below: + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. The names of its contributors may not be used to endorse or promote + * products derived from this software without specific prior written + * permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR + * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT + * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED + * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR + * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * The contents of this header was split off from videodev2.h. All control + * definitions should be added to this header, which is included by + * videodev2.h. + */ + +#ifndef __LINUX_V4L2_CONTROLS_H +#define __LINUX_V4L2_CONTROLS_H + +/* Control classes */ +#define V4L2_CTRL_CLASS_USER 0x00980000 /* Old-style 'user' controls */ +#define V4L2_CTRL_CLASS_MPEG 0x00990000 /* MPEG-compression controls */ +#define V4L2_CTRL_CLASS_CAMERA 0x009a0000 /* Camera class controls */ +#define V4L2_CTRL_CLASS_FM_TX 0x009b0000 /* FM Modulator controls */ +#define V4L2_CTRL_CLASS_FLASH 0x009c0000 /* Camera flash controls */ +#define V4L2_CTRL_CLASS_JPEG 0x009d0000 /* JPEG-compression controls */ +#define V4L2_CTRL_CLASS_IMAGE_SOURCE 0x009e0000 /* Image source controls */ +#define V4L2_CTRL_CLASS_IMAGE_PROC 0x009f0000 /* Image processing controls */ +#define V4L2_CTRL_CLASS_DV 0x00a00000 /* Digital Video controls */ +#define V4L2_CTRL_CLASS_FM_RX 0x00a10000 /* FM Receiver controls */ +#define V4L2_CTRL_CLASS_RF_TUNER 0x00a20000 /* RF tuner controls */ +#define V4L2_CTRL_CLASS_DETECT 0x00a30000 /* Detection controls */ + +/* User-class control IDs */ + +#define V4L2_CID_BASE (V4L2_CTRL_CLASS_USER | 0x900) +#define V4L2_CID_USER_BASE V4L2_CID_BASE +#define V4L2_CID_USER_CLASS (V4L2_CTRL_CLASS_USER | 1) +#define V4L2_CID_BRIGHTNESS (V4L2_CID_BASE+0) +#define V4L2_CID_CONTRAST (V4L2_CID_BASE+1) +#define V4L2_CID_SATURATION (V4L2_CID_BASE+2) +#define V4L2_CID_HUE (V4L2_CID_BASE+3) +#define V4L2_CID_AUDIO_VOLUME (V4L2_CID_BASE+5) +#define V4L2_CID_AUDIO_BALANCE (V4L2_CID_BASE+6) +#define V4L2_CID_AUDIO_BASS (V4L2_CID_BASE+7) +#define V4L2_CID_AUDIO_TREBLE (V4L2_CID_BASE+8) +#define V4L2_CID_AUDIO_MUTE (V4L2_CID_BASE+9) +#define V4L2_CID_AUDIO_LOUDNESS (V4L2_CID_BASE+10) +#define V4L2_CID_BLACK_LEVEL (V4L2_CID_BASE+11) /* Deprecated */ +#define V4L2_CID_AUTO_WHITE_BALANCE (V4L2_CID_BASE+12) +#define V4L2_CID_DO_WHITE_BALANCE (V4L2_CID_BASE+13) +#define V4L2_CID_RED_BALANCE (V4L2_CID_BASE+14) +#define V4L2_CID_BLUE_BALANCE (V4L2_CID_BASE+15) +#define V4L2_CID_GAMMA (V4L2_CID_BASE+16) +#define V4L2_CID_WHITENESS (V4L2_CID_GAMMA) /* Deprecated */ +#define V4L2_CID_EXPOSURE (V4L2_CID_BASE+17) +#define V4L2_CID_AUTOGAIN (V4L2_CID_BASE+18) +#define V4L2_CID_GAIN (V4L2_CID_BASE+19) +#define V4L2_CID_HFLIP (V4L2_CID_BASE+20) +#define V4L2_CID_VFLIP (V4L2_CID_BASE+21) + +#define V4L2_CID_POWER_LINE_FREQUENCY (V4L2_CID_BASE+24) +enum v4l2_power_line_frequency { + V4L2_CID_POWER_LINE_FREQUENCY_DISABLED = 0, + V4L2_CID_POWER_LINE_FREQUENCY_50HZ = 1, + V4L2_CID_POWER_LINE_FREQUENCY_60HZ = 2, + V4L2_CID_POWER_LINE_FREQUENCY_AUTO = 3, +}; +#define V4L2_CID_HUE_AUTO (V4L2_CID_BASE+25) +#define V4L2_CID_WHITE_BALANCE_TEMPERATURE (V4L2_CID_BASE+26) +#define V4L2_CID_SHARPNESS (V4L2_CID_BASE+27) +#define V4L2_CID_BACKLIGHT_COMPENSATION (V4L2_CID_BASE+28) +#define V4L2_CID_CHROMA_AGC (V4L2_CID_BASE+29) +#define V4L2_CID_COLOR_KILLER (V4L2_CID_BASE+30) +#define V4L2_CID_COLORFX (V4L2_CID_BASE+31) +enum v4l2_colorfx { + V4L2_COLORFX_NONE = 0, + V4L2_COLORFX_BW = 1, + V4L2_COLORFX_SEPIA = 2, + V4L2_COLORFX_NEGATIVE = 3, + V4L2_COLORFX_EMBOSS = 4, + V4L2_COLORFX_SKETCH = 5, + V4L2_COLORFX_SKY_BLUE = 6, + V4L2_COLORFX_GRASS_GREEN = 7, + V4L2_COLORFX_SKIN_WHITEN = 8, + V4L2_COLORFX_VIVID = 9, + V4L2_COLORFX_AQUA = 10, + V4L2_COLORFX_ART_FREEZE = 11, + V4L2_COLORFX_SILHOUETTE = 12, + V4L2_COLORFX_SOLARIZATION = 13, + V4L2_COLORFX_ANTIQUE = 14, + V4L2_COLORFX_SET_CBCR = 15, +}; +#define V4L2_CID_AUTOBRIGHTNESS (V4L2_CID_BASE+32) +#define V4L2_CID_BAND_STOP_FILTER (V4L2_CID_BASE+33) + +#define V4L2_CID_ROTATE (V4L2_CID_BASE+34) +#define V4L2_CID_BG_COLOR (V4L2_CID_BASE+35) + +#define V4L2_CID_CHROMA_GAIN (V4L2_CID_BASE+36) + +#define V4L2_CID_ILLUMINATORS_1 (V4L2_CID_BASE+37) +#define V4L2_CID_ILLUMINATORS_2 (V4L2_CID_BASE+38) + +#define V4L2_CID_MIN_BUFFERS_FOR_CAPTURE (V4L2_CID_BASE+39) +#define V4L2_CID_MIN_BUFFERS_FOR_OUTPUT (V4L2_CID_BASE+40) + +#define V4L2_CID_ALPHA_COMPONENT (V4L2_CID_BASE+41) +#define V4L2_CID_COLORFX_CBCR (V4L2_CID_BASE+42) + +/* last CID + 1 */ +#define V4L2_CID_LASTP1 (V4L2_CID_BASE+43) + +/* USER-class private control IDs */ + +/* The base for the meye driver controls. See linux/meye.h for the list + * of controls. We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_MEYE_BASE (V4L2_CID_USER_BASE + 0x1000) + +/* The base for the bttv driver controls. + * We reserve 32 controls for this driver. */ +#define V4L2_CID_USER_BTTV_BASE (V4L2_CID_USER_BASE + 0x1010) + + +/* The base for the s2255 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_S2255_BASE (V4L2_CID_USER_BASE + 0x1030) + +/* + * The base for the si476x driver controls. See include/media/drv-intf/si476x.h + * for the list of controls. Total of 16 controls is reserved for this driver + */ +#define V4L2_CID_USER_SI476X_BASE (V4L2_CID_USER_BASE + 0x1040) + +/* The base for the TI VPE driver controls. Total of 16 controls is reserved for + * this driver */ +#define V4L2_CID_USER_TI_VPE_BASE (V4L2_CID_USER_BASE + 0x1050) + +/* The base for the saa7134 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_SAA7134_BASE (V4L2_CID_USER_BASE + 0x1060) + +/* The base for the adv7180 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_ADV7180_BASE (V4L2_CID_USER_BASE + 0x1070) + +/* The base for the tc358743 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_TC358743_BASE (V4L2_CID_USER_BASE + 0x1080) + +/* MPEG-class control IDs */ +/* The MPEG controls are applicable to all codec controls + * and the 'MPEG' part of the define is historical */ + +#define V4L2_CID_MPEG_BASE (V4L2_CTRL_CLASS_MPEG | 0x900) +#define V4L2_CID_MPEG_CLASS (V4L2_CTRL_CLASS_MPEG | 1) + +/* MPEG streams, specific to multiplexed streams */ +#define V4L2_CID_MPEG_STREAM_TYPE (V4L2_CID_MPEG_BASE+0) +enum v4l2_mpeg_stream_type { + V4L2_MPEG_STREAM_TYPE_MPEG2_PS = 0, /* MPEG-2 program stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_TS = 1, /* MPEG-2 transport stream */ + V4L2_MPEG_STREAM_TYPE_MPEG1_SS = 2, /* MPEG-1 system stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_DVD = 3, /* MPEG-2 DVD-compatible stream */ + V4L2_MPEG_STREAM_TYPE_MPEG1_VCD = 4, /* MPEG-1 VCD-compatible stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_SVCD = 5, /* MPEG-2 SVCD-compatible stream */ +}; +#define V4L2_CID_MPEG_STREAM_PID_PMT (V4L2_CID_MPEG_BASE+1) +#define V4L2_CID_MPEG_STREAM_PID_AUDIO (V4L2_CID_MPEG_BASE+2) +#define V4L2_CID_MPEG_STREAM_PID_VIDEO (V4L2_CID_MPEG_BASE+3) +#define V4L2_CID_MPEG_STREAM_PID_PCR (V4L2_CID_MPEG_BASE+4) +#define V4L2_CID_MPEG_STREAM_PES_ID_AUDIO (V4L2_CID_MPEG_BASE+5) +#define V4L2_CID_MPEG_STREAM_PES_ID_VIDEO (V4L2_CID_MPEG_BASE+6) +#define V4L2_CID_MPEG_STREAM_VBI_FMT (V4L2_CID_MPEG_BASE+7) +enum v4l2_mpeg_stream_vbi_fmt { + V4L2_MPEG_STREAM_VBI_FMT_NONE = 0, /* No VBI in the MPEG stream */ + V4L2_MPEG_STREAM_VBI_FMT_IVTV = 1, /* VBI in private packets, IVTV format */ +}; + +/* MPEG audio controls specific to multiplexed streams */ +#define V4L2_CID_MPEG_AUDIO_SAMPLING_FREQ (V4L2_CID_MPEG_BASE+100) +enum v4l2_mpeg_audio_sampling_freq { + V4L2_MPEG_AUDIO_SAMPLING_FREQ_44100 = 0, + V4L2_MPEG_AUDIO_SAMPLING_FREQ_48000 = 1, + V4L2_MPEG_AUDIO_SAMPLING_FREQ_32000 = 2, +}; +#define V4L2_CID_MPEG_AUDIO_ENCODING (V4L2_CID_MPEG_BASE+101) +enum v4l2_mpeg_audio_encoding { + V4L2_MPEG_AUDIO_ENCODING_LAYER_1 = 0, + V4L2_MPEG_AUDIO_ENCODING_LAYER_2 = 1, + V4L2_MPEG_AUDIO_ENCODING_LAYER_3 = 2, + V4L2_MPEG_AUDIO_ENCODING_AAC = 3, + V4L2_MPEG_AUDIO_ENCODING_AC3 = 4, +}; +#define V4L2_CID_MPEG_AUDIO_L1_BITRATE (V4L2_CID_MPEG_BASE+102) +enum v4l2_mpeg_audio_l1_bitrate { + V4L2_MPEG_AUDIO_L1_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L1_BITRATE_64K = 1, + V4L2_MPEG_AUDIO_L1_BITRATE_96K = 2, + V4L2_MPEG_AUDIO_L1_BITRATE_128K = 3, + V4L2_MPEG_AUDIO_L1_BITRATE_160K = 4, + V4L2_MPEG_AUDIO_L1_BITRATE_192K = 5, + V4L2_MPEG_AUDIO_L1_BITRATE_224K = 6, + V4L2_MPEG_AUDIO_L1_BITRATE_256K = 7, + V4L2_MPEG_AUDIO_L1_BITRATE_288K = 8, + V4L2_MPEG_AUDIO_L1_BITRATE_320K = 9, + V4L2_MPEG_AUDIO_L1_BITRATE_352K = 10, + V4L2_MPEG_AUDIO_L1_BITRATE_384K = 11, + V4L2_MPEG_AUDIO_L1_BITRATE_416K = 12, + V4L2_MPEG_AUDIO_L1_BITRATE_448K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_L2_BITRATE (V4L2_CID_MPEG_BASE+103) +enum v4l2_mpeg_audio_l2_bitrate { + V4L2_MPEG_AUDIO_L2_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L2_BITRATE_48K = 1, + V4L2_MPEG_AUDIO_L2_BITRATE_56K = 2, + V4L2_MPEG_AUDIO_L2_BITRATE_64K = 3, + V4L2_MPEG_AUDIO_L2_BITRATE_80K = 4, + V4L2_MPEG_AUDIO_L2_BITRATE_96K = 5, + V4L2_MPEG_AUDIO_L2_BITRATE_112K = 6, + V4L2_MPEG_AUDIO_L2_BITRATE_128K = 7, + V4L2_MPEG_AUDIO_L2_BITRATE_160K = 8, + V4L2_MPEG_AUDIO_L2_BITRATE_192K = 9, + V4L2_MPEG_AUDIO_L2_BITRATE_224K = 10, + V4L2_MPEG_AUDIO_L2_BITRATE_256K = 11, + V4L2_MPEG_AUDIO_L2_BITRATE_320K = 12, + V4L2_MPEG_AUDIO_L2_BITRATE_384K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_L3_BITRATE (V4L2_CID_MPEG_BASE+104) +enum v4l2_mpeg_audio_l3_bitrate { + V4L2_MPEG_AUDIO_L3_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L3_BITRATE_40K = 1, + V4L2_MPEG_AUDIO_L3_BITRATE_48K = 2, + V4L2_MPEG_AUDIO_L3_BITRATE_56K = 3, + V4L2_MPEG_AUDIO_L3_BITRATE_64K = 4, + V4L2_MPEG_AUDIO_L3_BITRATE_80K = 5, + V4L2_MPEG_AUDIO_L3_BITRATE_96K = 6, + V4L2_MPEG_AUDIO_L3_BITRATE_112K = 7, + V4L2_MPEG_AUDIO_L3_BITRATE_128K = 8, + V4L2_MPEG_AUDIO_L3_BITRATE_160K = 9, + V4L2_MPEG_AUDIO_L3_BITRATE_192K = 10, + V4L2_MPEG_AUDIO_L3_BITRATE_224K = 11, + V4L2_MPEG_AUDIO_L3_BITRATE_256K = 12, + V4L2_MPEG_AUDIO_L3_BITRATE_320K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_MODE (V4L2_CID_MPEG_BASE+105) +enum v4l2_mpeg_audio_mode { + V4L2_MPEG_AUDIO_MODE_STEREO = 0, + V4L2_MPEG_AUDIO_MODE_JOINT_STEREO = 1, + V4L2_MPEG_AUDIO_MODE_DUAL = 2, + V4L2_MPEG_AUDIO_MODE_MONO = 3, +}; +#define V4L2_CID_MPEG_AUDIO_MODE_EXTENSION (V4L2_CID_MPEG_BASE+106) +enum v4l2_mpeg_audio_mode_extension { + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_4 = 0, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_8 = 1, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_12 = 2, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_16 = 3, +}; +#define V4L2_CID_MPEG_AUDIO_EMPHASIS (V4L2_CID_MPEG_BASE+107) +enum v4l2_mpeg_audio_emphasis { + V4L2_MPEG_AUDIO_EMPHASIS_NONE = 0, + V4L2_MPEG_AUDIO_EMPHASIS_50_DIV_15_uS = 1, + V4L2_MPEG_AUDIO_EMPHASIS_CCITT_J17 = 2, +}; +#define V4L2_CID_MPEG_AUDIO_CRC (V4L2_CID_MPEG_BASE+108) +enum v4l2_mpeg_audio_crc { + V4L2_MPEG_AUDIO_CRC_NONE = 0, + V4L2_MPEG_AUDIO_CRC_CRC16 = 1, +}; +#define V4L2_CID_MPEG_AUDIO_MUTE (V4L2_CID_MPEG_BASE+109) +#define V4L2_CID_MPEG_AUDIO_AAC_BITRATE (V4L2_CID_MPEG_BASE+110) +#define V4L2_CID_MPEG_AUDIO_AC3_BITRATE (V4L2_CID_MPEG_BASE+111) +enum v4l2_mpeg_audio_ac3_bitrate { + V4L2_MPEG_AUDIO_AC3_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_AC3_BITRATE_40K = 1, + V4L2_MPEG_AUDIO_AC3_BITRATE_48K = 2, + V4L2_MPEG_AUDIO_AC3_BITRATE_56K = 3, + V4L2_MPEG_AUDIO_AC3_BITRATE_64K = 4, + V4L2_MPEG_AUDIO_AC3_BITRATE_80K = 5, + V4L2_MPEG_AUDIO_AC3_BITRATE_96K = 6, + V4L2_MPEG_AUDIO_AC3_BITRATE_112K = 7, + V4L2_MPEG_AUDIO_AC3_BITRATE_128K = 8, + V4L2_MPEG_AUDIO_AC3_BITRATE_160K = 9, + V4L2_MPEG_AUDIO_AC3_BITRATE_192K = 10, + V4L2_MPEG_AUDIO_AC3_BITRATE_224K = 11, + V4L2_MPEG_AUDIO_AC3_BITRATE_256K = 12, + V4L2_MPEG_AUDIO_AC3_BITRATE_320K = 13, + V4L2_MPEG_AUDIO_AC3_BITRATE_384K = 14, + V4L2_MPEG_AUDIO_AC3_BITRATE_448K = 15, + V4L2_MPEG_AUDIO_AC3_BITRATE_512K = 16, + V4L2_MPEG_AUDIO_AC3_BITRATE_576K = 17, + V4L2_MPEG_AUDIO_AC3_BITRATE_640K = 18, +}; +#define V4L2_CID_MPEG_AUDIO_DEC_PLAYBACK (V4L2_CID_MPEG_BASE+112) +enum v4l2_mpeg_audio_dec_playback { + V4L2_MPEG_AUDIO_DEC_PLAYBACK_AUTO = 0, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_STEREO = 1, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_LEFT = 2, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_RIGHT = 3, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_MONO = 4, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_SWAPPED_STEREO = 5, +}; +#define V4L2_CID_MPEG_AUDIO_DEC_MULTILINGUAL_PLAYBACK (V4L2_CID_MPEG_BASE+113) + +/* MPEG video controls specific to multiplexed streams */ +#define V4L2_CID_MPEG_VIDEO_ENCODING (V4L2_CID_MPEG_BASE+200) +enum v4l2_mpeg_video_encoding { + V4L2_MPEG_VIDEO_ENCODING_MPEG_1 = 0, + V4L2_MPEG_VIDEO_ENCODING_MPEG_2 = 1, + V4L2_MPEG_VIDEO_ENCODING_MPEG_4_AVC = 2, +}; +#define V4L2_CID_MPEG_VIDEO_ASPECT (V4L2_CID_MPEG_BASE+201) +enum v4l2_mpeg_video_aspect { + V4L2_MPEG_VIDEO_ASPECT_1x1 = 0, + V4L2_MPEG_VIDEO_ASPECT_4x3 = 1, + V4L2_MPEG_VIDEO_ASPECT_16x9 = 2, + V4L2_MPEG_VIDEO_ASPECT_221x100 = 3, +}; +#define V4L2_CID_MPEG_VIDEO_B_FRAMES (V4L2_CID_MPEG_BASE+202) +#define V4L2_CID_MPEG_VIDEO_GOP_SIZE (V4L2_CID_MPEG_BASE+203) +#define V4L2_CID_MPEG_VIDEO_GOP_CLOSURE (V4L2_CID_MPEG_BASE+204) +#define V4L2_CID_MPEG_VIDEO_PULLDOWN (V4L2_CID_MPEG_BASE+205) +#define V4L2_CID_MPEG_VIDEO_BITRATE_MODE (V4L2_CID_MPEG_BASE+206) +enum v4l2_mpeg_video_bitrate_mode { + V4L2_MPEG_VIDEO_BITRATE_MODE_VBR = 0, + V4L2_MPEG_VIDEO_BITRATE_MODE_CBR = 1, +}; +#define V4L2_CID_MPEG_VIDEO_BITRATE (V4L2_CID_MPEG_BASE+207) +#define V4L2_CID_MPEG_VIDEO_BITRATE_PEAK (V4L2_CID_MPEG_BASE+208) +#define V4L2_CID_MPEG_VIDEO_TEMPORAL_DECIMATION (V4L2_CID_MPEG_BASE+209) +#define V4L2_CID_MPEG_VIDEO_MUTE (V4L2_CID_MPEG_BASE+210) +#define V4L2_CID_MPEG_VIDEO_MUTE_YUV (V4L2_CID_MPEG_BASE+211) +#define V4L2_CID_MPEG_VIDEO_DECODER_SLICE_INTERFACE (V4L2_CID_MPEG_BASE+212) +#define V4L2_CID_MPEG_VIDEO_DECODER_MPEG4_DEBLOCK_FILTER (V4L2_CID_MPEG_BASE+213) +#define V4L2_CID_MPEG_VIDEO_CYCLIC_INTRA_REFRESH_MB (V4L2_CID_MPEG_BASE+214) +#define V4L2_CID_MPEG_VIDEO_FRAME_RC_ENABLE (V4L2_CID_MPEG_BASE+215) +#define V4L2_CID_MPEG_VIDEO_HEADER_MODE (V4L2_CID_MPEG_BASE+216) +enum v4l2_mpeg_video_header_mode { + V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE = 0, + V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_1ST_FRAME = 1, + V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_I_FRAME = 2, +}; +#define V4L2_CID_MPEG_VIDEO_MAX_REF_PIC (V4L2_CID_MPEG_BASE+217) +#define V4L2_CID_MPEG_VIDEO_MB_RC_ENABLE (V4L2_CID_MPEG_BASE+218) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_BYTES (V4L2_CID_MPEG_BASE+219) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_MB (V4L2_CID_MPEG_BASE+220) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE (V4L2_CID_MPEG_BASE+221) +enum v4l2_mpeg_video_multi_slice_mode { + V4L2_MPEG_VIDEO_MULTI_SLICE_MODE_SINGLE = 0, + V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_MB = 1, + V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_BYTES = 2, + V4L2_MPEG_VIDEO_MULTI_SLICE_GOB = 3, +}; +#define V4L2_CID_MPEG_VIDEO_VBV_SIZE (V4L2_CID_MPEG_BASE+222) +#define V4L2_CID_MPEG_VIDEO_DEC_PTS (V4L2_CID_MPEG_BASE+223) +#define V4L2_CID_MPEG_VIDEO_DEC_FRAME (V4L2_CID_MPEG_BASE+224) +#define V4L2_CID_MPEG_VIDEO_VBV_DELAY (V4L2_CID_MPEG_BASE+225) +#define V4L2_CID_MPEG_VIDEO_REPEAT_SEQ_HEADER (V4L2_CID_MPEG_BASE+226) +#define V4L2_CID_MPEG_VIDEO_MV_H_SEARCH_RANGE (V4L2_CID_MPEG_BASE+227) +#define V4L2_CID_MPEG_VIDEO_MV_V_SEARCH_RANGE (V4L2_CID_MPEG_BASE+228) +#define V4L2_CID_MPEG_VIDEO_FORCE_KEY_FRAME (V4L2_CID_MPEG_BASE+229) + +#define V4L2_CID_MPEG_VIDEO_H263_I_FRAME_QP (V4L2_CID_MPEG_BASE+300) +#define V4L2_CID_MPEG_VIDEO_H263_P_FRAME_QP (V4L2_CID_MPEG_BASE+301) +#define V4L2_CID_MPEG_VIDEO_H263_B_FRAME_QP (V4L2_CID_MPEG_BASE+302) +#define V4L2_CID_MPEG_VIDEO_H263_MIN_QP (V4L2_CID_MPEG_BASE+303) +#define V4L2_CID_MPEG_VIDEO_H263_MAX_QP (V4L2_CID_MPEG_BASE+304) +#define V4L2_CID_MPEG_VIDEO_H264_I_FRAME_QP (V4L2_CID_MPEG_BASE+350) +#define V4L2_CID_MPEG_VIDEO_H264_P_FRAME_QP (V4L2_CID_MPEG_BASE+351) +#define V4L2_CID_MPEG_VIDEO_H264_B_FRAME_QP (V4L2_CID_MPEG_BASE+352) +#define V4L2_CID_MPEG_VIDEO_H264_MIN_QP (V4L2_CID_MPEG_BASE+353) +#define V4L2_CID_MPEG_VIDEO_H264_MAX_QP (V4L2_CID_MPEG_BASE+354) +#define V4L2_CID_MPEG_VIDEO_H264_8X8_TRANSFORM (V4L2_CID_MPEG_BASE+355) +#define V4L2_CID_MPEG_VIDEO_H264_CPB_SIZE (V4L2_CID_MPEG_BASE+356) +#define V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE (V4L2_CID_MPEG_BASE+357) +enum v4l2_mpeg_video_h264_entropy_mode { + V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CAVLC = 0, + V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_I_PERIOD (V4L2_CID_MPEG_BASE+358) +#define V4L2_CID_MPEG_VIDEO_H264_LEVEL (V4L2_CID_MPEG_BASE+359) +enum v4l2_mpeg_video_h264_level { + V4L2_MPEG_VIDEO_H264_LEVEL_1_0 = 0, + V4L2_MPEG_VIDEO_H264_LEVEL_1B = 1, + V4L2_MPEG_VIDEO_H264_LEVEL_1_1 = 2, + V4L2_MPEG_VIDEO_H264_LEVEL_1_2 = 3, + V4L2_MPEG_VIDEO_H264_LEVEL_1_3 = 4, + V4L2_MPEG_VIDEO_H264_LEVEL_2_0 = 5, + V4L2_MPEG_VIDEO_H264_LEVEL_2_1 = 6, + V4L2_MPEG_VIDEO_H264_LEVEL_2_2 = 7, + V4L2_MPEG_VIDEO_H264_LEVEL_3_0 = 8, + V4L2_MPEG_VIDEO_H264_LEVEL_3_1 = 9, + V4L2_MPEG_VIDEO_H264_LEVEL_3_2 = 10, + V4L2_MPEG_VIDEO_H264_LEVEL_4_0 = 11, + V4L2_MPEG_VIDEO_H264_LEVEL_4_1 = 12, + V4L2_MPEG_VIDEO_H264_LEVEL_4_2 = 13, + V4L2_MPEG_VIDEO_H264_LEVEL_5_0 = 14, + V4L2_MPEG_VIDEO_H264_LEVEL_5_1 = 15, + V4L2_MPEG_VIDEO_H264_LEVEL_5_2 = 16, +#define V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN \ + V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN + V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA (V4L2_CID_MPEG_BASE+360) +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA (V4L2_CID_MPEG_BASE+361) +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE (V4L2_CID_MPEG_BASE+362) +enum v4l2_mpeg_video_h264_loop_filter_mode { + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_ENABLED = 0, + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED = 1, + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED_AT_SLICE_BOUNDARY = 2, +}; +#define V4L2_CID_MPEG_VIDEO_H264_PROFILE (V4L2_CID_MPEG_BASE+363) +enum v4l2_mpeg_video_h264_profile { + V4L2_MPEG_VIDEO_H264_PROFILE_BASELINE = 0, + V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_BASELINE = 1, + V4L2_MPEG_VIDEO_H264_PROFILE_MAIN = 2, + V4L2_MPEG_VIDEO_H264_PROFILE_EXTENDED = 3, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH = 4, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10 = 5, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422 = 6, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_PREDICTIVE = 7, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10_INTRA = 8, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422_INTRA = 9, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_INTRA = 10, + V4L2_MPEG_VIDEO_H264_PROFILE_CAVLC_444_INTRA = 11, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_BASELINE = 12, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH = 13, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH_INTRA = 14, + V4L2_MPEG_VIDEO_H264_PROFILE_STEREO_HIGH = 15, + V4L2_MPEG_VIDEO_H264_PROFILE_MULTIVIEW_HIGH = 16, + V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_HIGH = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_HEIGHT (V4L2_CID_MPEG_BASE+364) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_WIDTH (V4L2_CID_MPEG_BASE+365) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_ENABLE (V4L2_CID_MPEG_BASE+366) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_IDC (V4L2_CID_MPEG_BASE+367) +enum v4l2_mpeg_video_h264_vui_sar_idc { + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_UNSPECIFIED = 0, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_1x1 = 1, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_12x11 = 2, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_10x11 = 3, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_16x11 = 4, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_40x33 = 5, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_24x11 = 6, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_20x11 = 7, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_32x11 = 8, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_80x33 = 9, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_18x11 = 10, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_15x11 = 11, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_64x33 = 12, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_160x99 = 13, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_4x3 = 14, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_3x2 = 15, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_2x1 = 16, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_EXTENDED = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FRAME_PACKING (V4L2_CID_MPEG_BASE+368) +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_CURRENT_FRAME_0 (V4L2_CID_MPEG_BASE+369) +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE (V4L2_CID_MPEG_BASE+370) +enum v4l2_mpeg_video_h264_sei_fp_arrangement_type { + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_CHECKERBOARD = 0, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_COLUMN = 1, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_ROW = 2, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_SIDE_BY_SIDE = 3, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TOP_BOTTOM = 4, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TEMPORAL = 5, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO (V4L2_CID_MPEG_BASE+371) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_MAP_TYPE (V4L2_CID_MPEG_BASE+372) +enum v4l2_mpeg_video_h264_fmo_map_type { + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_INTERLEAVED_SLICES = 0, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_SCATTERED_SLICES = 1, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_FOREGROUND_WITH_LEFT_OVER = 2, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_BOX_OUT = 3, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_RASTER_SCAN = 4, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_WIPE_SCAN = 5, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_EXPLICIT = 6, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO_SLICE_GROUP (V4L2_CID_MPEG_BASE+373) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_DIRECTION (V4L2_CID_MPEG_BASE+374) +enum v4l2_mpeg_video_h264_fmo_change_dir { + V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_RIGHT = 0, + V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_LEFT = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_RATE (V4L2_CID_MPEG_BASE+375) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_RUN_LENGTH (V4L2_CID_MPEG_BASE+376) +#define V4L2_CID_MPEG_VIDEO_H264_ASO (V4L2_CID_MPEG_BASE+377) +#define V4L2_CID_MPEG_VIDEO_H264_ASO_SLICE_ORDER (V4L2_CID_MPEG_BASE+378) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING (V4L2_CID_MPEG_BASE+379) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_TYPE (V4L2_CID_MPEG_BASE+380) +enum v4l2_mpeg_video_h264_hierarchical_coding_type { + V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_B = 0, + V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_P = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER (V4L2_CID_MPEG_BASE+381) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER_QP (V4L2_CID_MPEG_BASE+382) +#define V4L2_CID_MPEG_VIDEO_MPEG4_I_FRAME_QP (V4L2_CID_MPEG_BASE+400) +#define V4L2_CID_MPEG_VIDEO_MPEG4_P_FRAME_QP (V4L2_CID_MPEG_BASE+401) +#define V4L2_CID_MPEG_VIDEO_MPEG4_B_FRAME_QP (V4L2_CID_MPEG_BASE+402) +#define V4L2_CID_MPEG_VIDEO_MPEG4_MIN_QP (V4L2_CID_MPEG_BASE+403) +#define V4L2_CID_MPEG_VIDEO_MPEG4_MAX_QP (V4L2_CID_MPEG_BASE+404) +#define V4L2_CID_MPEG_VIDEO_MPEG4_LEVEL (V4L2_CID_MPEG_BASE+405) +enum v4l2_mpeg_video_mpeg4_level { + V4L2_MPEG_VIDEO_MPEG4_LEVEL_0 = 0, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_0B = 1, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_1 = 2, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_2 = 3, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_3 = 4, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_3B = 5, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_4 = 6, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_5 = 7, +}; +#define V4L2_CID_MPEG_VIDEO_MPEG4_PROFILE (V4L2_CID_MPEG_BASE+406) +enum v4l2_mpeg_video_mpeg4_profile { + V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE = 0, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_SIMPLE = 1, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_CORE = 2, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE_SCALABLE = 3, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_CODING_EFFICIENCY = 4, +}; +#define V4L2_CID_MPEG_VIDEO_MPEG4_QPEL (V4L2_CID_MPEG_BASE+407) + +/* Control IDs for VP8 streams + * Although VP8 is not part of MPEG we add these controls to the MPEG class + * as that class is already handling other video compression standards + */ +#define V4L2_CID_MPEG_VIDEO_VPX_NUM_PARTITIONS (V4L2_CID_MPEG_BASE+500) +enum v4l2_vp8_num_partitions { + V4L2_CID_MPEG_VIDEO_VPX_1_PARTITION = 0, + V4L2_CID_MPEG_VIDEO_VPX_2_PARTITIONS = 1, + V4L2_CID_MPEG_VIDEO_VPX_4_PARTITIONS = 2, + V4L2_CID_MPEG_VIDEO_VPX_8_PARTITIONS = 3, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_IMD_DISABLE_4X4 (V4L2_CID_MPEG_BASE+501) +#define V4L2_CID_MPEG_VIDEO_VPX_NUM_REF_FRAMES (V4L2_CID_MPEG_BASE+502) +enum v4l2_vp8_num_ref_frames { + V4L2_CID_MPEG_VIDEO_VPX_1_REF_FRAME = 0, + V4L2_CID_MPEG_VIDEO_VPX_2_REF_FRAME = 1, + V4L2_CID_MPEG_VIDEO_VPX_3_REF_FRAME = 2, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_LEVEL (V4L2_CID_MPEG_BASE+503) +#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_SHARPNESS (V4L2_CID_MPEG_BASE+504) +#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_REF_PERIOD (V4L2_CID_MPEG_BASE+505) +#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_SEL (V4L2_CID_MPEG_BASE+506) +enum v4l2_vp8_golden_frame_sel { + V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_PREV = 0, + V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_REF_PERIOD = 1, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_MIN_QP (V4L2_CID_MPEG_BASE+507) +#define V4L2_CID_MPEG_VIDEO_VPX_MAX_QP (V4L2_CID_MPEG_BASE+508) +#define V4L2_CID_MPEG_VIDEO_VPX_I_FRAME_QP (V4L2_CID_MPEG_BASE+509) +#define V4L2_CID_MPEG_VIDEO_VPX_P_FRAME_QP (V4L2_CID_MPEG_BASE+510) +#define V4L2_CID_MPEG_VIDEO_VPX_PROFILE (V4L2_CID_MPEG_BASE+511) + +/* MPEG-class control IDs specific to the CX2341x driver as defined by V4L2 */ +#define V4L2_CID_MPEG_CX2341X_BASE (V4L2_CTRL_CLASS_MPEG | 0x1000) +#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+0) +enum v4l2_mpeg_cx2341x_video_spatial_filter_mode { + V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_MANUAL = 0, + V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_AUTO = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+1) +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+2) +enum v4l2_mpeg_cx2341x_video_luma_spatial_filter_type { + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_VERT = 2, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_HV_SEPARABLE = 3, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_SYM_NON_SEPARABLE = 4, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+3) +enum v4l2_mpeg_cx2341x_video_chroma_spatial_filter_type { + V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+4) +enum v4l2_mpeg_cx2341x_video_temporal_filter_mode { + V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_MANUAL = 0, + V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_AUTO = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+5) +#define V4L2_CID_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+6) +enum v4l2_mpeg_cx2341x_video_median_filter_type { + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR = 1, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_VERT = 2, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR_VERT = 3, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_DIAG = 4, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+7) +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+8) +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+9) +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+10) +#define V4L2_CID_MPEG_CX2341X_STREAM_INSERT_NAV_PACKETS (V4L2_CID_MPEG_CX2341X_BASE+11) + +/* MPEG-class control IDs specific to the Samsung MFC 5.1 driver as defined by V4L2 */ +#define V4L2_CID_MPEG_MFC51_BASE (V4L2_CTRL_CLASS_MPEG | 0x1100) + +#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY (V4L2_CID_MPEG_MFC51_BASE+0) +#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY_ENABLE (V4L2_CID_MPEG_MFC51_BASE+1) +#define V4L2_CID_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE (V4L2_CID_MPEG_MFC51_BASE+2) +enum v4l2_mpeg_mfc51_video_frame_skip_mode { + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_DISABLED = 0, + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_LEVEL_LIMIT = 1, + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_BUF_LIMIT = 2, +}; +#define V4L2_CID_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE (V4L2_CID_MPEG_MFC51_BASE+3) +enum v4l2_mpeg_mfc51_video_force_frame_type { + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_DISABLED = 0, + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_I_FRAME = 1, + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_NOT_CODED = 2, +}; +#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING (V4L2_CID_MPEG_MFC51_BASE+4) +#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING_YUV (V4L2_CID_MPEG_MFC51_BASE+5) +#define V4L2_CID_MPEG_MFC51_VIDEO_RC_FIXED_TARGET_BIT (V4L2_CID_MPEG_MFC51_BASE+6) +#define V4L2_CID_MPEG_MFC51_VIDEO_RC_REACTION_COEFF (V4L2_CID_MPEG_MFC51_BASE+7) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_ACTIVITY (V4L2_CID_MPEG_MFC51_BASE+50) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_DARK (V4L2_CID_MPEG_MFC51_BASE+51) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_SMOOTH (V4L2_CID_MPEG_MFC51_BASE+52) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_STATIC (V4L2_CID_MPEG_MFC51_BASE+53) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_NUM_REF_PIC_FOR_P (V4L2_CID_MPEG_MFC51_BASE+54) + +/* MPEG-class control IDs specific to the msm_vidc driver */ +#define V4L2_CID_MPEG_MSM_VIDC_BASE (V4L2_CTRL_CLASS_MPEG | 0x2000) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PICTYPE_DEC_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+0) +enum v4l2_mpeg_vidc_video_pictype_dec_mode { + V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_OFF = 0, + V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_ON = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_KEEP_ASPECT_RATIO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+1) + +#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+2) +enum v4l2_mpeg_vidc_video_stream_format { + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_STARTCODES = 0, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_NAL_PER_BUFFER = 1, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_BYTE_LENGTH = 2, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_TWO_BYTE_LENGTH = 3, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_FOUR_BYTE_LENGTH = 4, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_OUTPUT_ORDER (V4L2_CID_MPEG_MSM_VIDC_BASE+3) +enum v4l2_mpeg_vidc_video_output_order { + V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DISPLAY = 0, + V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DECODE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_RATE (V4L2_CID_MPEG_MSM_VIDC_BASE+4) +#define V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD (V4L2_CID_MPEG_MSM_VIDC_BASE+5) +#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+6) +#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+7) +#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_IFRAME (V4L2_CID_MPEG_MSM_VIDC_BASE+8) + +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL (V4L2_CID_MPEG_MSM_VIDC_BASE+9) +enum v4l2_mpeg_vidc_video_rate_control { + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_OFF = 0, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_VFR = 1, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR = 2, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_VFR = 3, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_CFR = 4, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR = 5, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR = 6, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CQ = 7, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR \ + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR \ + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR + +#define V4L2_CID_MPEG_VIDC_VIDEO_ROTATION (V4L2_CID_MPEG_MSM_VIDC_BASE+10) +enum v4l2_mpeg_vidc_video_rotation { + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_90 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_180 = 2, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_270 = 3, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+11) +enum v4l2_mpeg_vidc_h264_cabac_model { + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0 = 0, + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_1 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_2 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+12) +enum v4l2_mpeg_vidc_video_intra_refresh_mode { + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC = 1, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_RANDOM = 2, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_ADAPTIVE = 3, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC_ADAPTIVE = 4, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_IR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE+13) + +#define V4L2_CID_MPEG_VIDC_VIDEO_AU_DELIMITER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 14) +enum v4l2_mpeg_vidc_video_au_delimiter { + V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_ENABLED = 1 +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 15) +enum v4l2_mpeg_vidc_video_sync_frame_decode { + V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_ENABLE = 1 +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE (V4L2_CID_MPEG_MSM_VIDC_BASE+16) +#define V4L2_CID_MPEG_VIDC_VIDEO_EXTRADATA \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 17) +enum v4l2_mpeg_vidc_extradata { + V4L2_MPEG_VIDC_EXTRADATA_NONE = 0, + V4L2_MPEG_VIDC_EXTRADATA_MB_QUANTIZATION = 1, + V4L2_MPEG_VIDC_EXTRADATA_INTERLACE_VIDEO = 2, + V4L2_MPEG_VIDC_EXTRADATA_VC1_FRAMEDISP = 3, + V4L2_MPEG_VIDC_EXTRADATA_VC1_SEQDISP = 4, + V4L2_MPEG_VIDC_EXTRADATA_TIMESTAMP = 5, + V4L2_MPEG_VIDC_EXTRADATA_S3D_FRAME_PACKING = 6, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_RATE = 7, + V4L2_MPEG_VIDC_EXTRADATA_PANSCAN_WINDOW = 8, + V4L2_MPEG_VIDC_EXTRADATA_RECOVERY_POINT_SEI = 9, + V4L2_MPEG_VIDC_EXTRADATA_MULTISLICE_INFO = 10, + V4L2_MPEG_VIDC_EXTRADATA_NUM_CONCEALED_MB = 11, + V4L2_MPEG_VIDC_EXTRADATA_METADATA_FILLER = 12, + V4L2_MPEG_VIDC_EXTRADATA_INPUT_CROP = 13, + V4L2_MPEG_VIDC_EXTRADATA_DIGITAL_ZOOM = 14, + V4L2_MPEG_VIDC_EXTRADATA_ASPECT_RATIO = 15, + V4L2_MPEG_VIDC_EXTRADATA_MPEG2_SEQDISP = 16, + V4L2_MPEG_VIDC_EXTRADATA_STREAM_USERDATA = 17, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_QP = 18, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_BITS_INFO = 19, + V4L2_MPEG_VIDC_EXTRADATA_LTR = 20, + V4L2_MPEG_VIDC_EXTRADATA_METADATA_MBI = 21, + V4L2_MPEG_VIDC_EXTRADATA_VQZIP_SEI = 22, + V4L2_MPEG_VIDC_EXTRADATA_YUV_STATS = 23, + V4L2_MPEG_VIDC_EXTRADATA_ROI_QP = 24, +#define V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP \ + V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP + V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP = 25, +#define V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI \ + V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI + V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI = 26, +#define V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI \ + V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI + V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI = 27, +#define V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO \ + V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO + V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO = 28, +#define V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY \ + V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY + V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY = 29, +#define V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE \ + V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE + V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE = 30, +#define V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO \ + V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO + V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO = 31, +#define V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP \ + V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP + V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP = 32, +}; + +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_DELIVERY_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 18) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 19) +enum v4l2_mpeg_vidc_video_vui_timing_info { + V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_PROFILE_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 20) +enum v4l2_mpeg_vidc_video_vp8_profile_level { + V4L2_MPEG_VIDC_VIDEO_VP8_UNUSED, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_0, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_1, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_2, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_3, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 21) +enum v4l2_mpeg_vidc_video_preserve_text_quality { + V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 22) +enum v4l2_mpeg_vidc_video_decoder_multi_stream { + V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_PRIMARY = 0, + V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_SECONDARY = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE+23) +enum v4l2_mpeg_vidc_video_mpeg2_level { + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_0 = 0, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_2 = 2, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_3 = 3, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_PROFILE (V4L2_CID_MPEG_MSM_VIDC_BASE+24) +enum v4l2_mpeg_vidc_video_mpeg2_profile { + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SIMPLE = 0, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_MAIN = 1, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_422 = 2, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SNR_SCALABLE = 3, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SPATIAL_SCALABLE = 4, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_HIGH = 5, +}; + +enum v4l2_mpeg_vidc_video_mvc_layout { + V4L2_MPEG_VIDC_VIDEO_MVC_SEQUENTIAL = 0, + V4L2_MPEG_VIDC_VIDEO_MVC_TOP_BOTTOM = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 25) + +#define V4L2_CID_MPEG_VIDC_VIDEO_LTRMODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 26) + +enum v4l2_mpeg_vidc_video_ltrmode { + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_MANUAL = 1, + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_PERIODIC = 2 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_LTRCOUNT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 27) + +#define V4L2_CID_MPEG_VIDC_VIDEO_USELTRFRAME \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 28) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MARKLTRFRAME \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 29) + +#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_P_NUM_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 30) + +#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_OUTPUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+31) +enum v4l2_mpeg_vidc_video_alloc_mode_type { + V4L2_MPEG_VIDC_VIDEO_STATIC = 0, + V4L2_MPEG_VIDC_VIDEO_RING = 1, + V4L2_MPEG_VIDC_VIDEO_DYNAMIC = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 32) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 33) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 34) + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 35) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 36) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 37) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 38) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BUFFER_SIZE_LIMIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 39) + +enum vl42_mpeg_vidc_video_vpx_error_resilience { + V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_ENABLED = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 40) +enum v4l2_mpeg_video_hevc_profile { + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN = 0, + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN10 = 1, + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN_STILL_PIC = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 41) +enum v4l2_mpeg_video_hevc_level { + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_1 = 0, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2 = 2, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2 = 3, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2_1 = 4, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2_1 = 5, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3 = 6, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3 = 7, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3_1 = 8, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3_1 = 9, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4 = 10, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4 = 11, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4_1 = 12, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4_1 = 13, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5 = 14, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5 = 15, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_1 = 16, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_1 = 17, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_2 = 18, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_2 = 19, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6 = 20, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6 = 21, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_1 = 22, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_1 = 23, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_2 = 24, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_2 = 25, +#define V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN \ + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN = 26, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_B_NUM_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 42) + +#define V4L2_CID_MPEG_VIDC_VIDEO_HYBRID_HIERP_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 43) + +#define V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 44) + +enum v4l2_mpeg_vidc_video_dpb_color_format { + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_NONE = 0, + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_UBWC = 1, + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_TP10_UBWC = 2 +}; + +#define V4L2_CID_VIDC_QBUF_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 45) +enum v4l2_vidc_qbuf_mode { + V4L2_VIDC_QBUF_STANDARD = 0, + V4L2_VIDC_QBUF_BATCHED = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MAX_HIERP_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 46) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BASELAYER_ID \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 47) + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_WIDTH \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 48) + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_HEIGHT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 49) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 50) + +enum v4l2_mpeg_vidc_video_vqzip_sei_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_LAYER_BITRATE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 51) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 52) + +enum v4l2_mpeg_vidc_video_priority { + V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_ENABLE = 0, + V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_OPERATING_RATE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 53) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_TYPE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 54) + +enum v4l2_mpeg_vidc_video_venc_bitrate_type_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 55) + +enum v4l2_cid_mpeg_vidc_video_vpe_csc_type_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 56) + +enum v4l2_mpeg_vidc_video_lowlatency_mode { + V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_WIDTH \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 57) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_HEIGHT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 58) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 59) +enum v4l2_mpeg_vidc_video_h264_transform_8x8 { + V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_COLOR_SPACE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 60) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 61) + +enum v4l2_cid_mpeg_vidc_video_full_range { + V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TRANSFER_CHARS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 62) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MATRIX_COEFFS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 63) + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_TYPE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 64) + +#define V4L2_CID_MPEG_VIDC_VIDEO_LAYER_ID \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 65) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 66) +enum v4l2_mpeg_vidc_video_vp9_profile { + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_UNUSED = 0, + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P0 = 1, + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P2_10 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 67) +enum v4l2_mpeg_vidc_video_vp9_level { + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_UNUSED = 0, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_11 = 2, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_2 = 3, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_21 = 4, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_3 = 5, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_31 = 6, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_4 = 7, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_41 = 8, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_5 = 9, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_51 = 10, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MB_ERROR_MAP_REPORTING \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 68) +#define V4L2_CID_MPEG_VIDC_VIDEO_CONTINUE_DATA_TRANSFER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 69) + +#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_INPUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 70) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_ASSEMBLY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 71) +enum v4l2_mpeg_vidc_video_assembly { + V4L2_MPEG_VIDC_FRAME_ASSEMBLY_DISABLE = 0, + V4L2_MPEG_VIDC_FRAME_ASSEMBLY_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_H263_PROFILE\ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 72) +enum v4l2_mpeg_vidc_video_h263_profile { + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BASELINE = 0, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_H320CODING = 1, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BACKWARDCOMPATIBLE = 2, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV2 = 3, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV3 = 4, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHCOMPRESSION = 5, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERNET = 6, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERLACE = 7, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHLATENCY = 8, +}; + +#define V4L2_CID_MPEG_VIDEO_MIN_QP_PACKED \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 97) +#define V4L2_CID_MPEG_VIDEO_MAX_QP_PACKED \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 98) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 99) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 100) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 101) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 102) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 103) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 104) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 105) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 106) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 107) +#define V4L2_CID_MPEG_VIDC_VIDEO_QP_MASK \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 108) + +enum v4l2_mpeg_vidc_video_venc_iframesize_type { + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_DEFAULT, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_MEDIUM, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_HUGE, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_UNLIMITED, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_8BIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 109) +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_10BIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 110) + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 111) + +enum v4l2_mpeg_vidc_video_tme_profile { + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_0 = 0, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_1 = 1, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_2 = 2, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_3 = 3, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 112) + +enum v4l2_mpeg_vidc_video_tme_level { + V4L2_MPEG_VIDC_VIDEO_TME_LEVEL_INTEGER = 0, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PAYLOAD_VERSION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 113) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_CUSTOM_MATRIX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 114) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FLIP (V4L2_CID_MPEG_MSM_VIDC_BASE + 115) +enum v4l2_mpeg_vidc_video_flip { + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_HORI = 1, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_VERT = 2, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_BOTH = 3, +}; + +/* HDR SEI INFO related control IDs and definitions*/ +#define V4L2_MPEG_VIDC_VENC_HDR_INFO_ENABLED 1 +#define V4L2_MPEG_VIDC_VENC_HDR_INFO_DISABLED 0 + +#define V4L2_CID_MPEG_VIDC_VENC_HDR_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 116) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_00 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 117) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_01 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 118) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_10 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 119) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_11 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 120) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_20 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 121) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_21 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 122) +#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_X \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 123) +#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_Y \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 124) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_DISP_LUM \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 125) +#define V4L2_CID_MPEG_VIDC_VENC_MIN_DISP_LUM \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 126) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_CLL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 127) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_FLL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 128) + +#define V4L2_CID_MPEG_VIDC_SET_PERF_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 129) +enum v4l2_mpeg_vidc_perf_level { + V4L2_CID_MPEG_VIDC_PERF_LEVEL_NOMINAL = 0, + V4L2_CID_MPEG_VIDC_PERF_LEVEL_PERFORMANCE = 1, + V4L2_CID_MPEG_VIDC_PERF_LEVEL_TURBO = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 130) +#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_REF (V4L2_CID_MPEG_MSM_VIDC_BASE + 131) +#define V4L2_CID_MPEG_VIDC_VIDEO_CIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 132) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 135) + +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_GOB \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 136) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 137) +enum v4l2_mpeg_vidc_video_h264_vui_bitstream_restrict { + V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 138) +enum v4l2_mpeg_vidc_video_deinterlace { + V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_DISABLED = 0, + V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG4_TIME_RESOLUTION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 139) + +#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_SEQ_HEADER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 140) + +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 141) +enum v4l2_mpeg_vidc_video_rate_control_timestamp_mode { + V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_HONOR = 0, + V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_IGNORE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 142) +enum vl42_mpeg_vidc_video_enable_initial_qp { + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_IFRAME = 0x1, + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_PFRAME = 0x2, + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_BFRAME = 0x4, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_I_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 143) + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_P_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 144) + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_B_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 145) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 146) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PERF_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 147) +enum v4l2_mpeg_vidc_video_perf_mode { + V4L2_MPEG_VIDC_VIDEO_PERF_MAX_QUALITY = 1, + V4L2_MPEG_VIDC_VIDEO_PERF_POWER_SAVE = 2 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MBI_STATISTICS_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 148) + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONFIG_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 149) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_PIC_ORDER_CNT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 150) + +#define V4L2_CID_MPEG_VIDC_VIDEO_SCS_THRESHOLD \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 151) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MVC_BUFFER_LAYOUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 152) + + +#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE_SCALING_THRESHOLD \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 153) + +#define V4L2_CID_MPEG_VIDC_VIDEO_NON_SECURE_OUTPUT2 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 154) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MIN_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 155) +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MAX_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 156) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H263_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE + 157) +enum v4l2_mpeg_vidc_video_h263_level { + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_1_0 = 0, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_2_0 = 1, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_3_0 = 2, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_0 = 3, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_5 = 4, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_5_0 = 5, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_6_0 = 6, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_7_0 = 7, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_POST_LOOP_DEBLOCKER_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 158) + + +#define V4L2_CID_MPEG_VIDC_VIDEO_DIVX_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+159) + +enum v4l2_mpeg_vidc_video_divx_format_type { + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_4 = 0, + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_5 = 1, + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_6 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_QUALITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+160) + +#define V4L2_CID_MPEG_VIDC_IMG_GRID_DIMENSION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+161) + +enum v4l2_mpeg_vidc_video_mbi_statistics_mode { + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_DEFAULT = 0, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_1 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_2 = 2, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_3 = 3, +}; + +enum vl42_mpeg_vidc_video_h264_svc_nal { + V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_DISABLED = 0, + V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_ENABLED = 1, +}; + +enum v4l2_mpeg_vidc_video_h264_vui_timing_info { + V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_ENABLED = 1 +}; + +/* Camera class control IDs */ + +#define V4L2_CID_CAMERA_CLASS_BASE (V4L2_CTRL_CLASS_CAMERA | 0x900) +#define V4L2_CID_CAMERA_CLASS (V4L2_CTRL_CLASS_CAMERA | 1) + +#define V4L2_CID_EXPOSURE_AUTO (V4L2_CID_CAMERA_CLASS_BASE+1) +enum v4l2_exposure_auto_type { + V4L2_EXPOSURE_AUTO = 0, + V4L2_EXPOSURE_MANUAL = 1, + V4L2_EXPOSURE_SHUTTER_PRIORITY = 2, + V4L2_EXPOSURE_APERTURE_PRIORITY = 3 +}; +#define V4L2_CID_EXPOSURE_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+2) +#define V4L2_CID_EXPOSURE_AUTO_PRIORITY (V4L2_CID_CAMERA_CLASS_BASE+3) + +#define V4L2_CID_PAN_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+4) +#define V4L2_CID_TILT_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+5) +#define V4L2_CID_PAN_RESET (V4L2_CID_CAMERA_CLASS_BASE+6) +#define V4L2_CID_TILT_RESET (V4L2_CID_CAMERA_CLASS_BASE+7) + +#define V4L2_CID_PAN_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+8) +#define V4L2_CID_TILT_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+9) + +#define V4L2_CID_FOCUS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+10) +#define V4L2_CID_FOCUS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+11) +#define V4L2_CID_FOCUS_AUTO (V4L2_CID_CAMERA_CLASS_BASE+12) + +#define V4L2_CID_ZOOM_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+13) +#define V4L2_CID_ZOOM_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+14) +#define V4L2_CID_ZOOM_CONTINUOUS (V4L2_CID_CAMERA_CLASS_BASE+15) + +#define V4L2_CID_PRIVACY (V4L2_CID_CAMERA_CLASS_BASE+16) + +#define V4L2_CID_IRIS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+17) +#define V4L2_CID_IRIS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+18) + +#define V4L2_CID_AUTO_EXPOSURE_BIAS (V4L2_CID_CAMERA_CLASS_BASE+19) + +#define V4L2_CID_AUTO_N_PRESET_WHITE_BALANCE (V4L2_CID_CAMERA_CLASS_BASE+20) +enum v4l2_auto_n_preset_white_balance { + V4L2_WHITE_BALANCE_MANUAL = 0, + V4L2_WHITE_BALANCE_AUTO = 1, + V4L2_WHITE_BALANCE_INCANDESCENT = 2, + V4L2_WHITE_BALANCE_FLUORESCENT = 3, + V4L2_WHITE_BALANCE_FLUORESCENT_H = 4, + V4L2_WHITE_BALANCE_HORIZON = 5, + V4L2_WHITE_BALANCE_DAYLIGHT = 6, + V4L2_WHITE_BALANCE_FLASH = 7, + V4L2_WHITE_BALANCE_CLOUDY = 8, + V4L2_WHITE_BALANCE_SHADE = 9, +}; + +#define V4L2_CID_WIDE_DYNAMIC_RANGE (V4L2_CID_CAMERA_CLASS_BASE+21) +#define V4L2_CID_IMAGE_STABILIZATION (V4L2_CID_CAMERA_CLASS_BASE+22) + +#define V4L2_CID_ISO_SENSITIVITY (V4L2_CID_CAMERA_CLASS_BASE+23) +#define V4L2_CID_ISO_SENSITIVITY_AUTO (V4L2_CID_CAMERA_CLASS_BASE+24) +enum v4l2_iso_sensitivity_auto_type { + V4L2_ISO_SENSITIVITY_MANUAL = 0, + V4L2_ISO_SENSITIVITY_AUTO = 1, +}; + +#define V4L2_CID_EXPOSURE_METERING (V4L2_CID_CAMERA_CLASS_BASE+25) +enum v4l2_exposure_metering { + V4L2_EXPOSURE_METERING_AVERAGE = 0, + V4L2_EXPOSURE_METERING_CENTER_WEIGHTED = 1, + V4L2_EXPOSURE_METERING_SPOT = 2, + V4L2_EXPOSURE_METERING_MATRIX = 3, +}; + +#define V4L2_CID_SCENE_MODE (V4L2_CID_CAMERA_CLASS_BASE+26) +enum v4l2_scene_mode { + V4L2_SCENE_MODE_NONE = 0, + V4L2_SCENE_MODE_BACKLIGHT = 1, + V4L2_SCENE_MODE_BEACH_SNOW = 2, + V4L2_SCENE_MODE_CANDLE_LIGHT = 3, + V4L2_SCENE_MODE_DAWN_DUSK = 4, + V4L2_SCENE_MODE_FALL_COLORS = 5, + V4L2_SCENE_MODE_FIREWORKS = 6, + V4L2_SCENE_MODE_LANDSCAPE = 7, + V4L2_SCENE_MODE_NIGHT = 8, + V4L2_SCENE_MODE_PARTY_INDOOR = 9, + V4L2_SCENE_MODE_PORTRAIT = 10, + V4L2_SCENE_MODE_SPORTS = 11, + V4L2_SCENE_MODE_SUNSET = 12, + V4L2_SCENE_MODE_TEXT = 13, +}; + +#define V4L2_CID_3A_LOCK (V4L2_CID_CAMERA_CLASS_BASE+27) +#define V4L2_LOCK_EXPOSURE (1 << 0) +#define V4L2_LOCK_WHITE_BALANCE (1 << 1) +#define V4L2_LOCK_FOCUS (1 << 2) + +#define V4L2_CID_AUTO_FOCUS_START (V4L2_CID_CAMERA_CLASS_BASE+28) +#define V4L2_CID_AUTO_FOCUS_STOP (V4L2_CID_CAMERA_CLASS_BASE+29) +#define V4L2_CID_AUTO_FOCUS_STATUS (V4L2_CID_CAMERA_CLASS_BASE+30) +#define V4L2_AUTO_FOCUS_STATUS_IDLE (0 << 0) +#define V4L2_AUTO_FOCUS_STATUS_BUSY (1 << 0) +#define V4L2_AUTO_FOCUS_STATUS_REACHED (1 << 1) +#define V4L2_AUTO_FOCUS_STATUS_FAILED (1 << 2) + +#define V4L2_CID_AUTO_FOCUS_RANGE (V4L2_CID_CAMERA_CLASS_BASE+31) +enum v4l2_auto_focus_range { + V4L2_AUTO_FOCUS_RANGE_AUTO = 0, + V4L2_AUTO_FOCUS_RANGE_NORMAL = 1, + V4L2_AUTO_FOCUS_RANGE_MACRO = 2, + V4L2_AUTO_FOCUS_RANGE_INFINITY = 3, +}; + +#define V4L2_CID_PAN_SPEED (V4L2_CID_CAMERA_CLASS_BASE+32) +#define V4L2_CID_TILT_SPEED (V4L2_CID_CAMERA_CLASS_BASE+33) + +/* FM Modulator class control IDs */ + +#define V4L2_CID_FM_TX_CLASS_BASE (V4L2_CTRL_CLASS_FM_TX | 0x900) +#define V4L2_CID_FM_TX_CLASS (V4L2_CTRL_CLASS_FM_TX | 1) + +#define V4L2_CID_RDS_TX_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 1) +#define V4L2_CID_RDS_TX_PI (V4L2_CID_FM_TX_CLASS_BASE + 2) +#define V4L2_CID_RDS_TX_PTY (V4L2_CID_FM_TX_CLASS_BASE + 3) +#define V4L2_CID_RDS_TX_PS_NAME (V4L2_CID_FM_TX_CLASS_BASE + 5) +#define V4L2_CID_RDS_TX_RADIO_TEXT (V4L2_CID_FM_TX_CLASS_BASE + 6) +#define V4L2_CID_RDS_TX_MONO_STEREO (V4L2_CID_FM_TX_CLASS_BASE + 7) +#define V4L2_CID_RDS_TX_ARTIFICIAL_HEAD (V4L2_CID_FM_TX_CLASS_BASE + 8) +#define V4L2_CID_RDS_TX_COMPRESSED (V4L2_CID_FM_TX_CLASS_BASE + 9) +#define V4L2_CID_RDS_TX_DYNAMIC_PTY (V4L2_CID_FM_TX_CLASS_BASE + 10) +#define V4L2_CID_RDS_TX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_TX_CLASS_BASE + 11) +#define V4L2_CID_RDS_TX_TRAFFIC_PROGRAM (V4L2_CID_FM_TX_CLASS_BASE + 12) +#define V4L2_CID_RDS_TX_MUSIC_SPEECH (V4L2_CID_FM_TX_CLASS_BASE + 13) +#define V4L2_CID_RDS_TX_ALT_FREQS_ENABLE (V4L2_CID_FM_TX_CLASS_BASE + 14) +#define V4L2_CID_RDS_TX_ALT_FREQS (V4L2_CID_FM_TX_CLASS_BASE + 15) + +#define V4L2_CID_AUDIO_LIMITER_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 64) +#define V4L2_CID_AUDIO_LIMITER_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 65) +#define V4L2_CID_AUDIO_LIMITER_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 66) + +#define V4L2_CID_AUDIO_COMPRESSION_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 80) +#define V4L2_CID_AUDIO_COMPRESSION_GAIN (V4L2_CID_FM_TX_CLASS_BASE + 81) +#define V4L2_CID_AUDIO_COMPRESSION_THRESHOLD (V4L2_CID_FM_TX_CLASS_BASE + 82) +#define V4L2_CID_AUDIO_COMPRESSION_ATTACK_TIME (V4L2_CID_FM_TX_CLASS_BASE + 83) +#define V4L2_CID_AUDIO_COMPRESSION_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 84) + +#define V4L2_CID_PILOT_TONE_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 96) +#define V4L2_CID_PILOT_TONE_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 97) +#define V4L2_CID_PILOT_TONE_FREQUENCY (V4L2_CID_FM_TX_CLASS_BASE + 98) + +#define V4L2_CID_TUNE_PREEMPHASIS (V4L2_CID_FM_TX_CLASS_BASE + 112) +enum v4l2_preemphasis { + V4L2_PREEMPHASIS_DISABLED = 0, + V4L2_PREEMPHASIS_50_uS = 1, + V4L2_PREEMPHASIS_75_uS = 2, +}; +#define V4L2_CID_TUNE_POWER_LEVEL (V4L2_CID_FM_TX_CLASS_BASE + 113) +#define V4L2_CID_TUNE_ANTENNA_CAPACITOR (V4L2_CID_FM_TX_CLASS_BASE + 114) + + +/* Flash and privacy (indicator) light controls */ + +#define V4L2_CID_FLASH_CLASS_BASE (V4L2_CTRL_CLASS_FLASH | 0x900) +#define V4L2_CID_FLASH_CLASS (V4L2_CTRL_CLASS_FLASH | 1) + +#define V4L2_CID_FLASH_LED_MODE (V4L2_CID_FLASH_CLASS_BASE + 1) +enum v4l2_flash_led_mode { + V4L2_FLASH_LED_MODE_NONE, + V4L2_FLASH_LED_MODE_FLASH, + V4L2_FLASH_LED_MODE_TORCH, +}; + +#define V4L2_CID_FLASH_STROBE_SOURCE (V4L2_CID_FLASH_CLASS_BASE + 2) +enum v4l2_flash_strobe_source { + V4L2_FLASH_STROBE_SOURCE_SOFTWARE, + V4L2_FLASH_STROBE_SOURCE_EXTERNAL, +}; + +#define V4L2_CID_FLASH_STROBE (V4L2_CID_FLASH_CLASS_BASE + 3) +#define V4L2_CID_FLASH_STROBE_STOP (V4L2_CID_FLASH_CLASS_BASE + 4) +#define V4L2_CID_FLASH_STROBE_STATUS (V4L2_CID_FLASH_CLASS_BASE + 5) + +#define V4L2_CID_FLASH_TIMEOUT (V4L2_CID_FLASH_CLASS_BASE + 6) +#define V4L2_CID_FLASH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 7) +#define V4L2_CID_FLASH_TORCH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 8) +#define V4L2_CID_FLASH_INDICATOR_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 9) + +#define V4L2_CID_FLASH_FAULT (V4L2_CID_FLASH_CLASS_BASE + 10) +#define V4L2_FLASH_FAULT_OVER_VOLTAGE (1 << 0) +#define V4L2_FLASH_FAULT_TIMEOUT (1 << 1) +#define V4L2_FLASH_FAULT_OVER_TEMPERATURE (1 << 2) +#define V4L2_FLASH_FAULT_SHORT_CIRCUIT (1 << 3) +#define V4L2_FLASH_FAULT_OVER_CURRENT (1 << 4) +#define V4L2_FLASH_FAULT_INDICATOR (1 << 5) +#define V4L2_FLASH_FAULT_UNDER_VOLTAGE (1 << 6) +#define V4L2_FLASH_FAULT_INPUT_VOLTAGE (1 << 7) +#define V4L2_FLASH_FAULT_LED_OVER_TEMPERATURE (1 << 8) + +#define V4L2_CID_FLASH_CHARGE (V4L2_CID_FLASH_CLASS_BASE + 11) +#define V4L2_CID_FLASH_READY (V4L2_CID_FLASH_CLASS_BASE + 12) + + +/* JPEG-class control IDs */ + +#define V4L2_CID_JPEG_CLASS_BASE (V4L2_CTRL_CLASS_JPEG | 0x900) +#define V4L2_CID_JPEG_CLASS (V4L2_CTRL_CLASS_JPEG | 1) + +#define V4L2_CID_JPEG_CHROMA_SUBSAMPLING (V4L2_CID_JPEG_CLASS_BASE + 1) +enum v4l2_jpeg_chroma_subsampling { + V4L2_JPEG_CHROMA_SUBSAMPLING_444 = 0, + V4L2_JPEG_CHROMA_SUBSAMPLING_422 = 1, + V4L2_JPEG_CHROMA_SUBSAMPLING_420 = 2, + V4L2_JPEG_CHROMA_SUBSAMPLING_411 = 3, + V4L2_JPEG_CHROMA_SUBSAMPLING_410 = 4, + V4L2_JPEG_CHROMA_SUBSAMPLING_GRAY = 5, +}; +#define V4L2_CID_JPEG_RESTART_INTERVAL (V4L2_CID_JPEG_CLASS_BASE + 2) +#define V4L2_CID_JPEG_COMPRESSION_QUALITY (V4L2_CID_JPEG_CLASS_BASE + 3) + +#define V4L2_CID_JPEG_ACTIVE_MARKER (V4L2_CID_JPEG_CLASS_BASE + 4) +#define V4L2_JPEG_ACTIVE_MARKER_APP0 (1 << 0) +#define V4L2_JPEG_ACTIVE_MARKER_APP1 (1 << 1) +#define V4L2_JPEG_ACTIVE_MARKER_COM (1 << 16) +#define V4L2_JPEG_ACTIVE_MARKER_DQT (1 << 17) +#define V4L2_JPEG_ACTIVE_MARKER_DHT (1 << 18) + + +/* Image source controls */ +#define V4L2_CID_IMAGE_SOURCE_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_SOURCE | 0x900) +#define V4L2_CID_IMAGE_SOURCE_CLASS (V4L2_CTRL_CLASS_IMAGE_SOURCE | 1) + +#define V4L2_CID_VBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 1) +#define V4L2_CID_HBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 2) +#define V4L2_CID_ANALOGUE_GAIN (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 3) +#define V4L2_CID_TEST_PATTERN_RED (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 4) +#define V4L2_CID_TEST_PATTERN_GREENR (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 5) +#define V4L2_CID_TEST_PATTERN_BLUE (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 6) +#define V4L2_CID_TEST_PATTERN_GREENB (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 7) + + +/* Image processing controls */ + +#define V4L2_CID_IMAGE_PROC_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_PROC | 0x900) +#define V4L2_CID_IMAGE_PROC_CLASS (V4L2_CTRL_CLASS_IMAGE_PROC | 1) + +#define V4L2_CID_LINK_FREQ (V4L2_CID_IMAGE_PROC_CLASS_BASE + 1) +#define V4L2_CID_PIXEL_RATE (V4L2_CID_IMAGE_PROC_CLASS_BASE + 2) +#define V4L2_CID_TEST_PATTERN (V4L2_CID_IMAGE_PROC_CLASS_BASE + 3) + + +/* DV-class control IDs defined by V4L2 */ +#define V4L2_CID_DV_CLASS_BASE (V4L2_CTRL_CLASS_DV | 0x900) +#define V4L2_CID_DV_CLASS (V4L2_CTRL_CLASS_DV | 1) + +#define V4L2_CID_DV_TX_HOTPLUG (V4L2_CID_DV_CLASS_BASE + 1) +#define V4L2_CID_DV_TX_RXSENSE (V4L2_CID_DV_CLASS_BASE + 2) +#define V4L2_CID_DV_TX_EDID_PRESENT (V4L2_CID_DV_CLASS_BASE + 3) +#define V4L2_CID_DV_TX_MODE (V4L2_CID_DV_CLASS_BASE + 4) +enum v4l2_dv_tx_mode { + V4L2_DV_TX_MODE_DVI_D = 0, + V4L2_DV_TX_MODE_HDMI = 1, +}; +#define V4L2_CID_DV_TX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 5) +enum v4l2_dv_rgb_range { + V4L2_DV_RGB_RANGE_AUTO = 0, + V4L2_DV_RGB_RANGE_LIMITED = 1, + V4L2_DV_RGB_RANGE_FULL = 2, +}; + +#define V4L2_CID_DV_TX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 6) +enum v4l2_dv_it_content_type { + V4L2_DV_IT_CONTENT_TYPE_GRAPHICS = 0, + V4L2_DV_IT_CONTENT_TYPE_PHOTO = 1, + V4L2_DV_IT_CONTENT_TYPE_CINEMA = 2, + V4L2_DV_IT_CONTENT_TYPE_GAME = 3, + V4L2_DV_IT_CONTENT_TYPE_NO_ITC = 4, +}; + +#define V4L2_CID_DV_RX_POWER_PRESENT (V4L2_CID_DV_CLASS_BASE + 100) +#define V4L2_CID_DV_RX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 101) +#define V4L2_CID_DV_RX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 102) + +#define V4L2_CID_FM_RX_CLASS_BASE (V4L2_CTRL_CLASS_FM_RX | 0x900) +#define V4L2_CID_FM_RX_CLASS (V4L2_CTRL_CLASS_FM_RX | 1) + +#define V4L2_CID_TUNE_DEEMPHASIS (V4L2_CID_FM_RX_CLASS_BASE + 1) +enum v4l2_deemphasis { + V4L2_DEEMPHASIS_DISABLED = V4L2_PREEMPHASIS_DISABLED, + V4L2_DEEMPHASIS_50_uS = V4L2_PREEMPHASIS_50_uS, + V4L2_DEEMPHASIS_75_uS = V4L2_PREEMPHASIS_75_uS, +}; + +#define V4L2_CID_RDS_RECEPTION (V4L2_CID_FM_RX_CLASS_BASE + 2) +#define V4L2_CID_RDS_RX_PTY (V4L2_CID_FM_RX_CLASS_BASE + 3) +#define V4L2_CID_RDS_RX_PS_NAME (V4L2_CID_FM_RX_CLASS_BASE + 4) +#define V4L2_CID_RDS_RX_RADIO_TEXT (V4L2_CID_FM_RX_CLASS_BASE + 5) +#define V4L2_CID_RDS_RX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_RX_CLASS_BASE + 6) +#define V4L2_CID_RDS_RX_TRAFFIC_PROGRAM (V4L2_CID_FM_RX_CLASS_BASE + 7) +#define V4L2_CID_RDS_RX_MUSIC_SPEECH (V4L2_CID_FM_RX_CLASS_BASE + 8) + +#define V4L2_CID_RF_TUNER_CLASS_BASE (V4L2_CTRL_CLASS_RF_TUNER | 0x900) +#define V4L2_CID_RF_TUNER_CLASS (V4L2_CTRL_CLASS_RF_TUNER | 1) + +#define V4L2_CID_RF_TUNER_BANDWIDTH_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 11) +#define V4L2_CID_RF_TUNER_BANDWIDTH (V4L2_CID_RF_TUNER_CLASS_BASE + 12) +#define V4L2_CID_RF_TUNER_RF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 32) +#define V4L2_CID_RF_TUNER_LNA_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 41) +#define V4L2_CID_RF_TUNER_LNA_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 42) +#define V4L2_CID_RF_TUNER_MIXER_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 51) +#define V4L2_CID_RF_TUNER_MIXER_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 52) +#define V4L2_CID_RF_TUNER_IF_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 61) +#define V4L2_CID_RF_TUNER_IF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 62) +#define V4L2_CID_RF_TUNER_PLL_LOCK (V4L2_CID_RF_TUNER_CLASS_BASE + 91) + + +/* Detection-class control IDs defined by V4L2 */ +#define V4L2_CID_DETECT_CLASS_BASE (V4L2_CTRL_CLASS_DETECT | 0x900) +#define V4L2_CID_DETECT_CLASS (V4L2_CTRL_CLASS_DETECT | 1) + +#define V4L2_CID_DETECT_MD_MODE (V4L2_CID_DETECT_CLASS_BASE + 1) +enum v4l2_detect_md_mode { + V4L2_DETECT_MD_MODE_DISABLED = 0, + V4L2_DETECT_MD_MODE_GLOBAL = 1, + V4L2_DETECT_MD_MODE_THRESHOLD_GRID = 2, + V4L2_DETECT_MD_MODE_REGION_GRID = 3, +}; +#define V4L2_CID_DETECT_MD_GLOBAL_THRESHOLD (V4L2_CID_DETECT_CLASS_BASE + 2) +#define V4L2_CID_DETECT_MD_THRESHOLD_GRID (V4L2_CID_DETECT_CLASS_BASE + 3) +#define V4L2_CID_DETECT_MD_REGION_GRID (V4L2_CID_DETECT_CLASS_BASE + 4) + +#endif diff --git a/third_party/openmax/include/OMX_Audio.h b/third_party/openmax/include/OMX_Audio.h deleted file mode 100644 index 0d455766c5..0000000000 --- a/third_party/openmax/include/OMX_Audio.h +++ /dev/null @@ -1,1312 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Audio.h - OpenMax IL version 1.1.2 - * The structures needed by Audio components to exchange - * parameters and configuration data with the componenmilts. - */ - -#ifndef OMX_Audio_h -#define OMX_Audio_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - -/** @defgroup midi MIDI - * @ingroup audio - */ - -/** @defgroup effects Audio effects - * @ingroup audio - */ - -/** @defgroup audio OpenMAX IL Audio Domain - * Structures for OpenMAX IL Audio domain - * @{ - */ - -/** Enumeration used to define the possible audio codings. - * If "OMX_AUDIO_CodingUnused" is selected, the coding selection must - * be done in a vendor specific way. Since this is for an audio - * processing element this enum is relevant. However, for another - * type of component other enums would be in this area. - */ -typedef enum OMX_AUDIO_CODINGTYPE { - OMX_AUDIO_CodingUnused = 0, /**< Placeholder value when coding is N/A */ - OMX_AUDIO_CodingAutoDetect, /**< auto detection of audio format */ - OMX_AUDIO_CodingPCM, /**< Any variant of PCM coding */ - OMX_AUDIO_CodingADPCM, /**< Any variant of ADPCM encoded data */ - OMX_AUDIO_CodingAMR, /**< Any variant of AMR encoded data */ - OMX_AUDIO_CodingGSMFR, /**< Any variant of GSM fullrate (i.e. GSM610) */ - OMX_AUDIO_CodingGSMEFR, /**< Any variant of GSM Enhanced Fullrate encoded data*/ - OMX_AUDIO_CodingGSMHR, /**< Any variant of GSM Halfrate encoded data */ - OMX_AUDIO_CodingPDCFR, /**< Any variant of PDC Fullrate encoded data */ - OMX_AUDIO_CodingPDCEFR, /**< Any variant of PDC Enhanced Fullrate encoded data */ - OMX_AUDIO_CodingPDCHR, /**< Any variant of PDC Halfrate encoded data */ - OMX_AUDIO_CodingTDMAFR, /**< Any variant of TDMA Fullrate encoded data (TIA/EIA-136-420) */ - OMX_AUDIO_CodingTDMAEFR, /**< Any variant of TDMA Enhanced Fullrate encoded data (TIA/EIA-136-410) */ - OMX_AUDIO_CodingQCELP8, /**< Any variant of QCELP 8kbps encoded data */ - OMX_AUDIO_CodingQCELP13, /**< Any variant of QCELP 13kbps encoded data */ - OMX_AUDIO_CodingEVRC, /**< Any variant of EVRC encoded data */ - OMX_AUDIO_CodingSMV, /**< Any variant of SMV encoded data */ - OMX_AUDIO_CodingG711, /**< Any variant of G.711 encoded data */ - OMX_AUDIO_CodingG723, /**< Any variant of G.723 dot 1 encoded data */ - OMX_AUDIO_CodingG726, /**< Any variant of G.726 encoded data */ - OMX_AUDIO_CodingG729, /**< Any variant of G.729 encoded data */ - OMX_AUDIO_CodingAAC, /**< Any variant of AAC encoded data */ - OMX_AUDIO_CodingMP3, /**< Any variant of MP3 encoded data */ - OMX_AUDIO_CodingSBC, /**< Any variant of SBC encoded data */ - OMX_AUDIO_CodingVORBIS, /**< Any variant of VORBIS encoded data */ - OMX_AUDIO_CodingWMA, /**< Any variant of WMA encoded data */ - OMX_AUDIO_CodingRA, /**< Any variant of RA encoded data */ - OMX_AUDIO_CodingMIDI, /**< Any variant of MIDI encoded data */ - OMX_AUDIO_CodingAC3, /**< Any variant of AC3 encoded data */ - OMX_AUDIO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CodingMax = 0x7FFFFFFF -} OMX_AUDIO_CODINGTYPE; - - -/** The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output audio - * path. If additional information is needed to define the parameters of the - * port (such as frequency), additional structures must be sent such as the - * OMX_AUDIO_PARAM_PCMMODETYPE structure to supply the extra parameters for the port. - */ -typedef struct OMX_AUDIO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; /**< MIME type of data for the port */ - OMX_NATIVE_DEVICETYPE pNativeRender; /** < platform specific reference - for an output device, - otherwise this field is 0 */ - OMX_BOOL bFlagErrorConcealment; /**< Turns on error concealment if it is - supported by the OMX component */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this - port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PORTDEFINITIONTYPE; - - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_AUDIO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PARAM_PORTFORMATTYPE; - - -/** PCM mode type */ -typedef enum OMX_AUDIO_PCMMODETYPE { - OMX_AUDIO_PCMModeLinear = 0, /**< Linear PCM encoded data */ - OMX_AUDIO_PCMModeALaw, /**< A law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeMULaw, /**< Mu law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_PCMModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_PCMModeMax = 0x7FFFFFFF -} OMX_AUDIO_PCMMODETYPE; - - -typedef enum OMX_AUDIO_CHANNELTYPE { - OMX_AUDIO_ChannelNone = 0x0, /**< Unused or empty */ - OMX_AUDIO_ChannelLF = 0x1, /**< Left front */ - OMX_AUDIO_ChannelRF = 0x2, /**< Right front */ - OMX_AUDIO_ChannelCF = 0x3, /**< Center front */ - OMX_AUDIO_ChannelLS = 0x4, /**< Left surround */ - OMX_AUDIO_ChannelRS = 0x5, /**< Right surround */ - OMX_AUDIO_ChannelLFE = 0x6, /**< Low frequency effects */ - OMX_AUDIO_ChannelCS = 0x7, /**< Back surround */ - OMX_AUDIO_ChannelLR = 0x8, /**< Left rear. */ - OMX_AUDIO_ChannelRR = 0x9, /**< Right rear. */ - OMX_AUDIO_ChannelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELTYPE; - -#define OMX_AUDIO_MAXCHANNELS 16 /**< maximum number distinct audio channels that a buffer may contain */ -#define OMX_MIN_PCMPAYLOAD_MSEC 5 /**< Minimum audio buffer payload size for uncompressed (PCM) audio */ - -/** PCM format description */ -typedef struct OMX_AUDIO_PARAM_PCMMODETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels (e.g. 2 for stereo) */ - OMX_NUMERICALDATATYPE eNumData; /**< indicates PCM data as signed or unsigned */ - OMX_ENDIANTYPE eEndian; /**< indicates PCM data as little or big endian */ - OMX_BOOL bInterleaved; /**< True for normal interleaved data; false for - non-interleaved data (e.g. block data) */ - OMX_U32 nBitPerSample; /**< Bit per sample */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_AUDIO_PCMMODETYPE ePCMMode; /**< PCM mode enumeration */ - OMX_AUDIO_CHANNELTYPE eChannelMapping[OMX_AUDIO_MAXCHANNELS]; /**< Slot i contains channel defined by eChannelMap[i] */ - -} OMX_AUDIO_PARAM_PCMMODETYPE; - - -/** Audio channel mode. This is used by both AAC and MP3, although the names are more appropriate - * for the MP3. For example, JointStereo for MP3 is CouplingChannels for AAC. - */ -typedef enum OMX_AUDIO_CHANNELMODETYPE { - OMX_AUDIO_ChannelModeStereo = 0, /**< 2 channels, the bitrate allocation between those - two channels changes accordingly to each channel information */ - OMX_AUDIO_ChannelModeJointStereo, /**< mode that takes advantage of what is common between - 2 channels for higher compression gain */ - OMX_AUDIO_ChannelModeDual, /**< 2 mono-channels, each channel is encoded with half - the bitrate of the overall bitrate */ - OMX_AUDIO_ChannelModeMono, /**< Mono channel mode */ - OMX_AUDIO_ChannelModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelModeMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELMODETYPE; - - -typedef enum OMX_AUDIO_MP3STREAMFORMATTYPE { - OMX_AUDIO_MP3StreamFormatMP1Layer3 = 0, /**< MP3 Audio MPEG 1 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2Layer3, /**< MP3 Audio MPEG 2 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2_5Layer3, /**< MP3 Audio MPEG2.5 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MP3StreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MP3StreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MP3STREAMFORMATTYPE; - -/** MP3 params */ -typedef struct OMX_AUDIO_PARAM_MP3TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_MP3STREAMFORMATTYPE eFormat; /**< MP3 stream format */ -} OMX_AUDIO_PARAM_MP3TYPE; - - -typedef enum OMX_AUDIO_AACSTREAMFORMATTYPE { - OMX_AUDIO_AACStreamFormatMP2ADTS = 0, /**< AAC Audio Data Transport Stream 2 format */ - OMX_AUDIO_AACStreamFormatMP4ADTS, /**< AAC Audio Data Transport Stream 4 format */ - OMX_AUDIO_AACStreamFormatMP4LOAS, /**< AAC Low Overhead Audio Stream format */ - OMX_AUDIO_AACStreamFormatMP4LATM, /**< AAC Low overhead Audio Transport Multiplex */ - OMX_AUDIO_AACStreamFormatADIF, /**< AAC Audio Data Interchange Format */ - OMX_AUDIO_AACStreamFormatMP4FF, /**< AAC inside MPEG-4/ISO File Format */ - OMX_AUDIO_AACStreamFormatRAW, /**< AAC Raw Format */ - OMX_AUDIO_AACStreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACStreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACStreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AACSTREAMFORMATTYPE; - - -/** AAC mode type. Note that the term profile is used with the MPEG-2 - * standard and the term object type and profile is used with MPEG-4 */ -typedef enum OMX_AUDIO_AACPROFILETYPE{ - OMX_AUDIO_AACObjectNull = 0, /**< Null, not used */ - OMX_AUDIO_AACObjectMain = 1, /**< AAC Main object */ - OMX_AUDIO_AACObjectLC, /**< AAC Low Complexity object (AAC profile) */ - OMX_AUDIO_AACObjectSSR, /**< AAC Scalable Sample Rate object */ - OMX_AUDIO_AACObjectLTP, /**< AAC Long Term Prediction object */ - OMX_AUDIO_AACObjectHE, /**< AAC High Efficiency (object type SBR, HE-AAC profile) */ - OMX_AUDIO_AACObjectScalable, /**< AAC Scalable object */ - OMX_AUDIO_AACObjectERLC = 17, /**< ER AAC Low Complexity object (Error Resilient AAC-LC) */ - OMX_AUDIO_AACObjectLD = 23, /**< AAC Low Delay object (Error Resilient) */ - OMX_AUDIO_AACObjectHE_PS = 29, /**< AAC High Efficiency with Parametric Stereo coding (HE-AAC v2, object type PS) */ - OMX_AUDIO_AACObjectKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACObjectVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACObjectMax = 0x7FFFFFFF -} OMX_AUDIO_AACPROFILETYPE; - - -/** AAC tool usage (for nAACtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for encoder configuration and optional as decoder info output. - * For MP3, OMX_AUDIO_CHANNELMODETYPE is sufficient. */ -#define OMX_AUDIO_AACToolNone 0x00000000 /**< no AAC tools allowed (encoder config) or active (decoder info output) */ -#define OMX_AUDIO_AACToolMS 0x00000001 /**< MS: Mid/side joint coding tool allowed or active */ -#define OMX_AUDIO_AACToolIS 0x00000002 /**< IS: Intensity stereo tool allowed or active */ -#define OMX_AUDIO_AACToolTNS 0x00000004 /**< TNS: Temporal Noise Shaping tool allowed or active */ -#define OMX_AUDIO_AACToolPNS 0x00000008 /**< PNS: MPEG-4 Perceptual Noise substitution tool allowed or active */ -#define OMX_AUDIO_AACToolLTP 0x00000010 /**< LTP: MPEG-4 Long Term Prediction tool allowed or active */ -#define OMX_AUDIO_AACToolAll 0x7FFFFFFF /**< all AAC tools allowed or active (*/ - -/** MPEG-4 AAC error resilience (ER) tool usage (for nAACERtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for ER encoder configuration and optional as decoder info output */ -#define OMX_AUDIO_AACERNone 0x00000000 /**< no AAC ER tools allowed/used */ -#define OMX_AUDIO_AACERVCB11 0x00000001 /**< VCB11: Virtual Code Books for AAC section data */ -#define OMX_AUDIO_AACERRVLC 0x00000002 /**< RVLC: Reversible Variable Length Coding */ -#define OMX_AUDIO_AACERHCR 0x00000004 /**< HCR: Huffman Codeword Reordering */ -#define OMX_AUDIO_AACERAll 0x7FFFFFFF /**< all AAC ER tools allowed/used */ - - -/** AAC params */ -typedef struct OMX_AUDIO_PARAM_AACPROFILETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_U32 nFrameLength; /**< Frame length (in audio samples per channel) of the codec. - Can be 1024 or 960 (AAC-LC), 2048 (HE-AAC), 480 or 512 (AAC-LD). - Use 0 to let encoder decide */ - OMX_U32 nAACtools; /**< AAC tool usage */ - OMX_U32 nAACERtools; /**< MPEG-4 AAC error resilience tool usage */ - OMX_AUDIO_AACPROFILETYPE eAACProfile; /**< AAC profile enumeration */ - OMX_AUDIO_AACSTREAMFORMATTYPE eAACStreamFormat; /**< AAC stream format enumeration */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ -} OMX_AUDIO_PARAM_AACPROFILETYPE; - - -/** VORBIS params */ -typedef struct OMX_AUDIO_PARAM_VORBISTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the encoded data data. Use 0 for variable - rate or unknown bit rates. Encoding is set to the - bitrate closest to specified value (in bps) */ - OMX_U32 nMinBitRate; /**< Sets minimum bitrate (in bps). */ - OMX_U32 nMaxBitRate; /**< Sets maximum bitrate (in bps). */ - - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_S32 nQuality; /**< Sets encoding quality to n, between -1 (low) and 10 (high). - In the default mode of operation, teh quality level is 3. - Normal quality range is 0 - 10. */ - OMX_BOOL bManaged; /**< Set bitrate management mode. This turns off the - normal VBR encoding, but allows hard or soft bitrate - constraints to be enforced by the encoder. This mode can - be slower, and may also be lower quality. It is - primarily useful for streaming. */ - OMX_BOOL bDownmix; /**< Downmix input from stereo to mono (has no effect on - non-stereo streams). Useful for lower-bitrate encoding. */ -} OMX_AUDIO_PARAM_VORBISTYPE; - - -/** WMA Version */ -typedef enum OMX_AUDIO_WMAFORMATTYPE { - OMX_AUDIO_WMAFormatUnused = 0, /**< format unused or unknown */ - OMX_AUDIO_WMAFormat7, /**< Windows Media Audio format 7 */ - OMX_AUDIO_WMAFormat8, /**< Windows Media Audio format 8 */ - OMX_AUDIO_WMAFormat9, /**< Windows Media Audio format 9 */ - OMX_AUDIO_WMAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_WMAFORMATTYPE; - - -/** WMA Profile */ -typedef enum OMX_AUDIO_WMAPROFILETYPE { - OMX_AUDIO_WMAProfileUnused = 0, /**< profile unused or unknown */ - OMX_AUDIO_WMAProfileL1, /**< Windows Media audio version 9 profile L1 */ - OMX_AUDIO_WMAProfileL2, /**< Windows Media audio version 9 profile L2 */ - OMX_AUDIO_WMAProfileL3, /**< Windows Media audio version 9 profile L3 */ - OMX_AUDIO_WMAProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAProfileMax = 0x7FFFFFFF -} OMX_AUDIO_WMAPROFILETYPE; - - -/** WMA params */ -typedef struct OMX_AUDIO_PARAM_WMATYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_WMAFORMATTYPE eFormat; /**< Version of WMA stream / data */ - OMX_AUDIO_WMAPROFILETYPE eProfile; /**< Profile of WMA stream / data */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data */ - OMX_U16 nBlockAlign; /**< is the block alignment, or block size, in bytes of the audio codec */ - OMX_U16 nEncodeOptions; /**< WMA Type-specific data */ - OMX_U32 nSuperBlockAlign; /**< WMA Type-specific data */ -} OMX_AUDIO_PARAM_WMATYPE; - -/** - * RealAudio format - */ -typedef enum OMX_AUDIO_RAFORMATTYPE { - OMX_AUDIO_RAFormatUnused = 0, /**< Format unused or unknown */ - OMX_AUDIO_RA8, /**< RealAudio 8 codec */ - OMX_AUDIO_RA9, /**< RealAudio 9 codec */ - OMX_AUDIO_RA10_AAC, /**< MPEG-4 AAC codec for bitrates of more than 128kbps */ - OMX_AUDIO_RA10_CODEC, /**< RealAudio codec for bitrates less than 128 kbps */ - OMX_AUDIO_RA10_LOSSLESS, /**< RealAudio Lossless */ - OMX_AUDIO_RA10_MULTICHANNEL, /**< RealAudio Multichannel */ - OMX_AUDIO_RA10_VOICE, /**< RealAudio Voice for bitrates below 15 kbps */ - OMX_AUDIO_RAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_RAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_RAFORMATTYPE; - -/** RA (Real Audio) params */ -typedef struct OMX_AUDIO_PARAM_RATYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSamplingRate; /**< is the sampling rate of the source data */ - OMX_U32 nBitsPerFrame; /**< is the value for bits per frame */ - OMX_U32 nSamplePerFrame; /**< is the value for samples per frame */ - OMX_U32 nCouplingQuantBits; /**< is the number of coupling quantization bits in the stream */ - OMX_U32 nCouplingStartRegion; /**< is the coupling start region in the stream */ - OMX_U32 nNumRegions; /**< is the number of regions value */ - OMX_AUDIO_RAFORMATTYPE eFormat; /**< is the RealAudio audio format */ -} OMX_AUDIO_PARAM_RATYPE; - - -/** SBC Allocation Method Type */ -typedef enum OMX_AUDIO_SBCALLOCMETHODTYPE { - OMX_AUDIO_SBCAllocMethodLoudness, /**< Loudness allocation method */ - OMX_AUDIO_SBCAllocMethodSNR, /**< SNR allocation method */ - OMX_AUDIO_SBCAllocMethodKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_SBCAllocMethodVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_SBCAllocMethodMax = 0x7FFFFFFF -} OMX_AUDIO_SBCALLOCMETHODTYPE; - - -/** SBC params */ -typedef struct OMX_AUDIO_PARAM_SBCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBlocks; /**< Number of blocks */ - OMX_U32 nSubbands; /**< Number of subbands */ - OMX_U32 nBitPool; /**< Bitpool value */ - OMX_BOOL bEnableBitrate; /**< Use bitrate value instead of bitpool */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_SBCALLOCMETHODTYPE eSBCAllocType; /**< SBC Allocation method type */ -} OMX_AUDIO_PARAM_SBCTYPE; - - -/** ADPCM stream format parameters */ -typedef struct OMX_AUDIO_PARAM_ADPCMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitsPerSample; /**< Number of bits in each sample */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ -} OMX_AUDIO_PARAM_ADPCMTYPE; - - -/** G723 rate */ -typedef enum OMX_AUDIO_G723RATE { - OMX_AUDIO_G723ModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_G723ModeLow, /**< 5300 bps */ - OMX_AUDIO_G723ModeHigh, /**< 6300 bps */ - OMX_AUDIO_G723ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G723ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G723ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G723RATE; - - -/** G723 - Sample rate must be 8 KHz */ -typedef struct OMX_AUDIO_PARAM_G723TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G723RATE eBitRate; /**< todo: Should this be moved to a config? */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ - OMX_BOOL bPostFilter; /**< Enable Post Filter */ -} OMX_AUDIO_PARAM_G723TYPE; - - -/** ITU G726 (ADPCM) rate */ -typedef enum OMX_AUDIO_G726MODE { - OMX_AUDIO_G726ModeUnused = 0, /**< G726 Mode unused / unknown */ - OMX_AUDIO_G726Mode16, /**< 16 kbps */ - OMX_AUDIO_G726Mode24, /**< 24 kbps */ - OMX_AUDIO_G726Mode32, /**< 32 kbps, most common rate, also G721 */ - OMX_AUDIO_G726Mode40, /**< 40 kbps */ - OMX_AUDIO_G726ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G726ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G726ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G726MODE; - - -/** G.726 stream format parameters - must be at 8KHz */ -typedef struct OMX_AUDIO_PARAM_G726TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_G726MODE eG726Mode; -} OMX_AUDIO_PARAM_G726TYPE; - - -/** G729 coder type */ -typedef enum OMX_AUDIO_G729TYPE { - OMX_AUDIO_G729 = 0, /**< ITU G.729 encoded data */ - OMX_AUDIO_G729A, /**< ITU G.729 annex A encoded data */ - OMX_AUDIO_G729B, /**< ITU G.729 with annex B encoded data */ - OMX_AUDIO_G729AB, /**< ITU G.729 annexes A and B encoded data */ - OMX_AUDIO_G729KhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G729VendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G729Max = 0x7FFFFFFF -} OMX_AUDIO_G729TYPE; - - -/** G729 stream format parameters - fixed 6KHz sample rate */ -typedef struct OMX_AUDIO_PARAM_G729TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G729TYPE eBitType; -} OMX_AUDIO_PARAM_G729TYPE; - - -/** AMR Frame format */ -typedef enum OMX_AUDIO_AMRFRAMEFORMATTYPE { - OMX_AUDIO_AMRFrameFormatConformance = 0, /**< Frame Format is AMR Conformance - (Standard) Format */ - OMX_AUDIO_AMRFrameFormatIF1, /**< Frame Format is AMR Interface - Format 1 */ - OMX_AUDIO_AMRFrameFormatIF2, /**< Frame Format is AMR Interface - Format 2*/ - OMX_AUDIO_AMRFrameFormatFSF, /**< Frame Format is AMR File Storage - Format */ - OMX_AUDIO_AMRFrameFormatRTPPayload, /**< Frame Format is AMR Real-Time - Transport Protocol Payload Format */ - OMX_AUDIO_AMRFrameFormatITU, /**< Frame Format is ITU Format (added at Motorola request) */ - OMX_AUDIO_AMRFrameFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRFrameFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRFrameFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AMRFRAMEFORMATTYPE; - - -/** AMR band mode */ -typedef enum OMX_AUDIO_AMRBANDMODETYPE { - OMX_AUDIO_AMRBandModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_AMRBandModeNB0, /**< AMRNB Mode 0 = 4750 bps */ - OMX_AUDIO_AMRBandModeNB1, /**< AMRNB Mode 1 = 5150 bps */ - OMX_AUDIO_AMRBandModeNB2, /**< AMRNB Mode 2 = 5900 bps */ - OMX_AUDIO_AMRBandModeNB3, /**< AMRNB Mode 3 = 6700 bps */ - OMX_AUDIO_AMRBandModeNB4, /**< AMRNB Mode 4 = 7400 bps */ - OMX_AUDIO_AMRBandModeNB5, /**< AMRNB Mode 5 = 7950 bps */ - OMX_AUDIO_AMRBandModeNB6, /**< AMRNB Mode 6 = 10200 bps */ - OMX_AUDIO_AMRBandModeNB7, /**< AMRNB Mode 7 = 12200 bps */ - OMX_AUDIO_AMRBandModeWB0, /**< AMRWB Mode 0 = 6600 bps */ - OMX_AUDIO_AMRBandModeWB1, /**< AMRWB Mode 1 = 8850 bps */ - OMX_AUDIO_AMRBandModeWB2, /**< AMRWB Mode 2 = 12650 bps */ - OMX_AUDIO_AMRBandModeWB3, /**< AMRWB Mode 3 = 14250 bps */ - OMX_AUDIO_AMRBandModeWB4, /**< AMRWB Mode 4 = 15850 bps */ - OMX_AUDIO_AMRBandModeWB5, /**< AMRWB Mode 5 = 18250 bps */ - OMX_AUDIO_AMRBandModeWB6, /**< AMRWB Mode 6 = 19850 bps */ - OMX_AUDIO_AMRBandModeWB7, /**< AMRWB Mode 7 = 23050 bps */ - OMX_AUDIO_AMRBandModeWB8, /**< AMRWB Mode 8 = 23850 bps */ - OMX_AUDIO_AMRBandModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRBandModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRBandModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRBANDMODETYPE; - - -/** AMR Discontinuous Transmission mode */ -typedef enum OMX_AUDIO_AMRDTXMODETYPE { - OMX_AUDIO_AMRDTXModeOff = 0, /**< AMR Discontinuous Transmission Mode is disabled */ - OMX_AUDIO_AMRDTXModeOnVAD1, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 1 (VAD1) is enabled */ - OMX_AUDIO_AMRDTXModeOnVAD2, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 2 (VAD2) is enabled */ - OMX_AUDIO_AMRDTXModeOnAuto, /**< The codec will automatically select between - Off, VAD1 or VAD2 modes */ - - OMX_AUDIO_AMRDTXasEFR, /**< DTX as EFR instead of AMR standard (3GPP 26.101, frame type =8,9,10) */ - - OMX_AUDIO_AMRDTXModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRDTXModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRDTXModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRDTXMODETYPE; - - -/** AMR params */ -typedef struct OMX_AUDIO_PARAM_AMRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate read only field */ - OMX_AUDIO_AMRBANDMODETYPE eAMRBandMode; /**< AMR Band Mode enumeration */ - OMX_AUDIO_AMRDTXMODETYPE eAMRDTXMode; /**< AMR DTX Mode enumeration */ - OMX_AUDIO_AMRFRAMEFORMATTYPE eAMRFrameFormat; /**< AMR frame format enumeration */ -} OMX_AUDIO_PARAM_AMRTYPE; - - -/** GSM_FR (ETSI 06.10, 3GPP 46.010) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMFRTYPE; - - -/** GSM-HR (ETSI 06.20, 3GPP 46.020) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMHRTYPE; - - -/** GSM-EFR (ETSI 06.60, 3GPP 46.060) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMEFRTYPE; - - -/** TDMA FR (TIA/EIA-136-420, VSELP 7.95kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAFRTYPE; - - -/** TDMA EFR (TIA/EIA-136-410, ACELP 7.4kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAEFRTYPE; - - -/** PDC FR ( RCR-27, VSELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCFRTYPE; - - -/** PDC EFR ( RCR-27, ACELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCEFRTYPE; - -/** PDC HR ( RCR-27, PSI-CELP 3.45kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCHRTYPE; - - -/** CDMA Rate types */ -typedef enum OMX_AUDIO_CDMARATETYPE { - OMX_AUDIO_CDMARateBlank = 0, /**< CDMA encoded frame is blank */ - OMX_AUDIO_CDMARateFull, /**< CDMA encoded frame in full rate */ - OMX_AUDIO_CDMARateHalf, /**< CDMA encoded frame in half rate */ - OMX_AUDIO_CDMARateQuarter, /**< CDMA encoded frame in quarter rate */ - OMX_AUDIO_CDMARateEighth, /**< CDMA encoded frame in eighth rate (DTX)*/ - OMX_AUDIO_CDMARateErasure, /**< CDMA erasure frame */ - OMX_AUDIO_CDMARateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CDMARateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CDMARateMax = 0x7FFFFFFF -} OMX_AUDIO_CDMARATETYPE; - - -/** QCELP8 (TIA/EIA-96, up to 8kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP8TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP8TYPE; - - -/** QCELP13 ( CDMA, EIA/TIA-733, 13.3kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP13TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP13TYPE; - - -/** EVRC ( CDMA, EIA/TIA-127, RCELP up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_EVRCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< actual Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter */ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter */ -} OMX_AUDIO_PARAM_EVRCTYPE; - - -/** SMV ( up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_SMVTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 ??*/ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 ??*/ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter ??*/ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter ??*/ -} OMX_AUDIO_PARAM_SMVTYPE; - - -/** MIDI Format - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIFORMATTYPE -{ - OMX_AUDIO_MIDIFormatUnknown = 0, /**< MIDI Format unknown or don't care */ - OMX_AUDIO_MIDIFormatSMF0, /**< Standard MIDI File Type 0 */ - OMX_AUDIO_MIDIFormatSMF1, /**< Standard MIDI File Type 1 */ - OMX_AUDIO_MIDIFormatSMF2, /**< Standard MIDI File Type 2 */ - OMX_AUDIO_MIDIFormatSPMIDI, /**< SP-MIDI */ - OMX_AUDIO_MIDIFormatXMF0, /**< eXtensible Music Format type 0 */ - OMX_AUDIO_MIDIFormatXMF1, /**< eXtensible Music Format type 1 */ - OMX_AUDIO_MIDIFormatMobileXMF, /**< Mobile XMF (eXtensible Music Format type 2) */ - OMX_AUDIO_MIDIFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIFORMATTYPE; - - -/** MIDI params - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDITYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nFileSize; /**< size of the MIDI file in bytes, where the entire - MIDI file passed in, otherwise if 0x0, the MIDI data - is merged and streamed (instead of passed as an - entire MIDI file) */ - OMX_BU32 sMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_BOOL bLoadDefaultSound; /**< Whether to load default sound - bank at initialization */ - OMX_AUDIO_MIDIFORMATTYPE eMidiFormat; /**< Version of the MIDI file */ -} OMX_AUDIO_PARAM_MIDITYPE; - - -/** Type of the MIDI sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKTYPE { - OMX_AUDIO_MIDISoundBankUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankDLS1, /**< DLS version 1 */ - OMX_AUDIO_MIDISoundBankDLS2, /**< DLS version 2 */ - OMX_AUDIO_MIDISoundBankMobileDLSBase, /**< Mobile DLS, using the base functionality */ - OMX_AUDIO_MIDISoundBankMobileDLSPlusOptions, /**< Mobile DLS, using the specification-defined optional feature set */ - OMX_AUDIO_MIDISoundBankKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKTYPE; - - -/** Bank Layout describes how bank MSB & LSB are used in the DLS instrument definitions sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE { - OMX_AUDIO_MIDISoundBankLayoutUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankLayoutGM, /**< GS layout (based on bank MSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutGM2, /**< General MIDI 2 layout (using MSB 0x78/0x79, LSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutUser, /**< Does not conform to any bank numbering standards */ - OMX_AUDIO_MIDISoundBankLayoutKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankLayoutVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankLayoutMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE; - - -/** MIDI params to load/unload user soundbank - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nDLSIndex; /**< DLS file index to be loaded */ - OMX_U32 nDLSSize; /**< Size in bytes */ - OMX_PTR pDLSData; /**< Pointer to DLS file data */ - OMX_AUDIO_MIDISOUNDBANKTYPE eMidiSoundBank; /**< Midi sound bank type enumeration */ - OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE eMidiSoundBankLayout; /**< Midi sound bank layout enumeration */ -} OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE; - - -/** Structure for Live MIDI events and MIP messages. - * (MIP = Maximum Instantaneous Polyphony; part of the SP-MIDI standard.) - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nMidiEventSize; /**< Size of immediate MIDI events or MIP message in bytes */ - OMX_U8 nMidiEvents[1]; /**< MIDI event array to be rendered immediately, or an - array for the MIP message buffer, where the size is - indicated by nMidiEventSize */ -} OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE; - - -/** MIDI sound bank/ program pair in a given channel - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannel; /**< Valid channel values range from 1 to 16 */ - OMX_U16 nIDProgram; /**< Valid program ID range is 1 to 128 */ - OMX_U16 nIDSoundBank; /**< Sound bank ID */ - OMX_U32 nUserSoundBankIndex;/**< User soundbank index, easier to access soundbanks - by index if multiple banks are present */ -} OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE; - - -/** MIDI control - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDICONTROLTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BS32 sPitchTransposition; /**< Pitch transposition in semitones, stored as Q22.10 - format based on JAVA MMAPI (JSR-135) requirement */ - OMX_BU32 sPlayBackRate; /**< Relative playback rate, stored as Q14.17 fixed-point - number based on JSR-135 requirement */ - OMX_BU32 sTempo ; /**< Tempo in beats per minute (BPM), stored as Q22.10 - fixed-point number based on JSR-135 requirement */ - OMX_U32 nMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_U32 nNumRepeat; /**< Number of times to repeat playback */ - OMX_U32 nStopTime; /**< Time in milliseconds to indicate when playback - will stop automatically. Set to zero if not used */ - OMX_U16 nChannelMuteMask; /**< 16 bit mask for channel mute status */ - OMX_U16 nChannelSoloMask; /**< 16 bit mask for channel solo status */ - OMX_U32 nTrack0031MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 32-63 */ - OMX_U32 nTrack0031SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 32-63 */ - -} OMX_AUDIO_CONFIG_MIDICONTROLTYPE; - - -/** MIDI Playback States - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIPLAYBACKSTATETYPE { - OMX_AUDIO_MIDIPlayBackStateUnknown = 0, /**< Unknown state or state does not map to - other defined states */ - OMX_AUDIO_MIDIPlayBackStateClosedEngaged, /**< No MIDI resource is currently open. - The MIDI engine is currently processing - MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateParsing, /**< A MIDI resource is open and is being - primed. The MIDI engine is currently - processing MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateOpenEngaged, /**< A MIDI resource is open and primed but - not playing. The MIDI engine is currently - processing MIDI events. The transition to - this state is only possible from the - OMX_AUDIO_MIDIPlayBackStatePlaying state, - when the 'playback head' reaches the end - of media data or the playback stops due - to stop time set.*/ - OMX_AUDIO_MIDIPlayBackStatePlaying, /**< A MIDI resource is open and currently - playing. The MIDI engine is currently - processing MIDI events.*/ - OMX_AUDIO_MIDIPlayBackStatePlayingPartially, /**< Best-effort playback due to SP-MIDI/DLS - resource constraints */ - OMX_AUDIO_MIDIPlayBackStatePlayingSilently, /**< Due to system resource constraints and - SP-MIDI content constraints, there is - no audible MIDI content during playback - currently. The situation may change if - resources are freed later.*/ - OMX_AUDIO_MIDIPlayBackStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIPlayBackStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIPlayBackStateMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIPLAYBACKSTATETYPE; - - -/** MIDI status - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISTATUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nNumTracks; /**< Number of MIDI tracks in the file, read only field. - NOTE: May not return a meaningful value until the entire - file is parsed and buffered. */ - OMX_U32 nDuration; /**< The length of the currently open MIDI resource - in milliseconds. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nPosition; /**< Current Position of the MIDI resource being played - in milliseconds */ - OMX_BOOL bVibra; /**< Does Vibra track exist? NOTE: May not return a meaningful - value until the entire file is parsed and buffered. */ - OMX_U32 nNumMetaEvents; /**< Total number of MIDI Meta Events in the currently - open MIDI resource. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nNumActiveVoices; /**< Number of active voices in the currently playing - MIDI resource. NOTE: May not return a meaningful value until - the entire file is parsed and buffered. */ - OMX_AUDIO_MIDIPLAYBACKSTATETYPE eMIDIPlayBackState; /**< MIDI playback state enumeration, read only field */ -} OMX_AUDIO_CONFIG_MIDISTATUSTYPE; - - -/** MIDI Meta Event structure one per Meta Event. - * MIDI Meta Events are like audio metadata, except that they are interspersed - * with the MIDI content throughout the file and are not localized in the header. - * As such, it is necessary to retrieve information about these Meta Events from - * the engine, as it encounters these Meta Events within the MIDI content. - * For example, SMF files can have up to 14 types of MIDI Meta Events (copyright, - * author, default tempo, etc.) scattered throughout the file. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U8 nMetaEventType; /**< Meta Event Type, 7bits (i.e. 0 - 127) */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U32 nTrack; /**< track number for the meta event */ - OMX_U32 nPosition; /**< Position of the meta-event in milliseconds */ -} OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE; - - -/** MIDI Meta Event Data structure - one per Meta Event. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U8 nData[1]; /**< array of one or more bytes of meta data - as indicated by the nMetaEventSize field */ -} OMX_AUDIO_CONFIG__MIDIMETAEVENTDATATYPE; - - -/** Audio Volume adjustment for a port */ -typedef struct OMX_AUDIO_CONFIG_VOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) - or logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. The values - for volume are in mB (millibels = 1/100 dB) relative - to a gain of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ -} OMX_AUDIO_CONFIG_VOLUMETYPE; - - -/** Audio Volume adjustment for a channel */ -typedef struct OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply volume settings - to all channels */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) or - logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. - The values for volume are in mB - (millibels = 1/100 dB) relative to a gain - of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE; - - -/** Audio balance setting */ -typedef struct OMX_AUDIO_CONFIG_BALANCETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's balance. Select the - output port to adjust the master - balance. */ - OMX_S32 nBalance; /**< balance setting for this port - (-100 to 100, where -100 indicates - all left, and no right */ -} OMX_AUDIO_CONFIG_BALANCETYPE; - - -/** Audio Port mute */ -typedef struct OMX_AUDIO_CONFIG_MUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's mute. Select the - output port to adjust the master - mute. */ - OMX_BOOL bMute; /**< Mute setting for this port */ -} OMX_AUDIO_CONFIG_MUTETYPE; - - -/** Audio Channel mute */ -typedef struct OMX_AUDIO_CONFIG_CHANNELMUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply mute settings - to all channels */ - OMX_BOOL bMute; /**< Mute setting for this channel */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELMUTETYPE; - - - -/** Enable / Disable for loudness control, which boosts bass and to a - * smaller extent high end frequencies to compensate for hearing - * ability at the extreme ends of the audio spectrum - */ -typedef struct OMX_AUDIO_CONFIG_LOUDNESSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bLoudness; /**< Enable/disable for loudness */ -} OMX_AUDIO_CONFIG_LOUDNESSTYPE; - - -/** Enable / Disable for bass, which controls low frequencies - */ -typedef struct OMX_AUDIO_CONFIG_BASSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for bass control */ - OMX_S32 nBass; /**< bass setting for the port, as a - continuous value from -100 to 100 - (0 means no change in bass level)*/ -} OMX_AUDIO_CONFIG_BASSTYPE; - - -/** Enable / Disable for treble, which controls high frequencies tones - */ -typedef struct OMX_AUDIO_CONFIG_TREBLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for treble control */ - OMX_S32 nTreble; /**< treble setting for the port, as a - continuous value from -100 to 100 - (0 means no change in treble level) */ -} OMX_AUDIO_CONFIG_TREBLETYPE; - - -/** An equalizer is typically used for two reasons: to compensate for an - * sub-optimal frequency response of a system to make it sound more natural - * or to create intentionally some unnatural coloring to the sound to create - * an effect. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_EQUALIZERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for equalizer */ - OMX_BU32 sBandIndex; /**< Band number to be set. Upper Limit is - N-1, where N is the number of bands, lower limit is 0 */ - OMX_BU32 sCenterFreq; /**< Center frequecies in Hz. This is a - read only element and is used to determine - the lower, center and upper frequency of - this band. */ - OMX_BS32 sBandLevel; /**< band level in millibels */ -} OMX_AUDIO_CONFIG_EQUALIZERTYPE; - - -/** Stereo widening mode type - * @ingroup effects - */ -typedef enum OMX_AUDIO_STEREOWIDENINGTYPE { - OMX_AUDIO_StereoWideningHeadphones, /**< Stereo widening for loudspeakers */ - OMX_AUDIO_StereoWideningLoudspeakers, /**< Stereo widening for closely spaced loudspeakers */ - OMX_AUDIO_StereoWideningKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_StereoWideningVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_StereoWideningMax = 0x7FFFFFFF -} OMX_AUDIO_STEREOWIDENINGTYPE; - - -/** Control for stereo widening, which is a special 2-channel - * case of the audio virtualizer effect. For example, for 5.1-channel - * output, it translates to virtual surround sound. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for stereo widening control */ - OMX_AUDIO_STEREOWIDENINGTYPE eWideningType; /**< Stereo widening algorithm type */ - OMX_U32 nStereoWidening; /**< stereo widening setting for the port, - as a continuous value from 0 to 100 */ -} OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE; - - -/** The chorus effect (or ``choralizer'') is any signal processor which makes - * one sound source (such as a voice) sound like many such sources singing - * (or playing) in unison. Since performance in unison is never exact, chorus - * effects simulate this by making independently modified copies of the input - * signal. Modifications may include (1) delay, (2) frequency shift, and - * (3) amplitude modulation. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_CHORUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for chorus */ - OMX_BU32 sDelay; /**< average delay in milliseconds */ - OMX_BU32 sModulationRate; /**< rate of modulation in millihertz */ - OMX_U32 nModulationDepth; /**< depth of modulation as a percentage of - delay (i.e. 0 to 100) */ - OMX_BU32 nFeedback; /**< Feedback from chorus output to input in percentage */ -} OMX_AUDIO_CONFIG_CHORUSTYPE; - - -/** Reverberation is part of the reflected sound that follows the early - * reflections. In a typical room, this consists of a dense succession of - * echoes whose energy decays exponentially. The reverberation effect structure - * as defined here includes both (early) reflections as well as (late) reverberations. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_REVERBERATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for reverberation control */ - OMX_BS32 sRoomLevel; /**< Intensity level for the whole room effect - (i.e. both early reflections and late - reverberation) in millibels */ - OMX_BS32 sRoomHighFreqLevel; /**< Attenuation at high frequencies - relative to the intensity at low - frequencies in millibels */ - OMX_BS32 sReflectionsLevel; /**< Intensity level of early reflections - (relative to room value), in millibels */ - OMX_BU32 sReflectionsDelay; /**< Delay time of the first reflection relative - to the direct path, in milliseconds */ - OMX_BS32 sReverbLevel; /**< Intensity level of late reverberation - relative to room level, in millibels */ - OMX_BU32 sReverbDelay; /**< Time delay from the first early reflection - to the beginning of the late reverberation - section, in milliseconds */ - OMX_BU32 sDecayTime; /**< Late reverberation decay time at low - frequencies, in milliseconds */ - OMX_BU32 nDecayHighFreqRatio; /**< Ratio of high frequency decay time relative - to low frequency decay time in percent */ - OMX_U32 nDensity; /**< Modal density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_U32 nDiffusion; /**< Echo density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_BU32 sReferenceHighFreq; /**< Reference high frequency in Hertz. This is - the frequency used as the reference for all - the high-frequency settings above */ - -} OMX_AUDIO_CONFIG_REVERBERATIONTYPE; - - -/** Possible settings for the Echo Cancelation structure to use - * @ingroup effects - */ -typedef enum OMX_AUDIO_ECHOCANTYPE { - OMX_AUDIO_EchoCanOff = 0, /**< Echo Cancellation is disabled */ - OMX_AUDIO_EchoCanNormal, /**< Echo Cancellation normal operation - - echo from plastics and face */ - OMX_AUDIO_EchoCanHFree, /**< Echo Cancellation optimized for - Hands Free operation */ - OMX_AUDIO_EchoCanCarKit, /**< Echo Cancellation optimized for - Car Kit (longer echo) */ - OMX_AUDIO_EchoCanKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_EchoCanVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_EchoCanMax = 0x7FFFFFFF -} OMX_AUDIO_ECHOCANTYPE; - - -/** Enable / Disable for echo cancelation, which removes undesired echo's - * from the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_AUDIO_ECHOCANTYPE eEchoCancelation; /**< Echo cancelation settings */ -} OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE; - - -/** Enable / Disable for noise reduction, which undesired noise from - * the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bNoiseReduction; /**< Enable/disable for noise reduction */ -} OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_Component.h b/third_party/openmax/include/OMX_Component.h deleted file mode 100644 index d5956405e2..0000000000 --- a/third_party/openmax/include/OMX_Component.h +++ /dev/null @@ -1,579 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Component.h - OpenMax IL version 1.1.2 - * The OMX_Component header file contains the definitions used to define - * the public interface of a component. This header file is intended to - * be used by both the application and the component. - */ - -#ifndef OMX_Component_h -#define OMX_Component_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include -#include -#include -#include - -/** @ingroup comp */ -typedef enum OMX_PORTDOMAINTYPE { - OMX_PortDomainAudio, - OMX_PortDomainVideo, - OMX_PortDomainImage, - OMX_PortDomainOther, - OMX_PortDomainKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_PortDomainVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_PortDomainMax = 0x7ffffff -} OMX_PORTDOMAINTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /**< Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - OMX_DIRTYPE eDir; /**< Direction (input or output) of this port */ - OMX_U32 nBufferCountActual; /**< The actual number of buffers allocated on this port */ - OMX_U32 nBufferCountMin; /**< The minimum number of buffers this port requires */ - OMX_U32 nBufferSize; /**< Size, in bytes, for buffers to be used for this channel */ - OMX_BOOL bEnabled; /**< Ports default to enabled and are enabled/disabled by - OMX_CommandPortEnable/OMX_CommandPortDisable. - When disabled a port is unpopulated. A disabled port - is not populated with buffers on a transition to IDLE. */ - OMX_BOOL bPopulated; /**< Port is populated with all of its buffers as indicated by - nBufferCountActual. A disabled port is always unpopulated. - An enabled port is populated on a transition to OMX_StateIdle - and unpopulated on a transition to loaded. */ - OMX_PORTDOMAINTYPE eDomain; /**< Domain of the port. Determines the contents of metadata below. */ - union { - OMX_AUDIO_PORTDEFINITIONTYPE audio; - OMX_VIDEO_PORTDEFINITIONTYPE video; - OMX_IMAGE_PORTDEFINITIONTYPE image; - OMX_OTHER_PORTDEFINITIONTYPE other; - } format; - OMX_BOOL bBuffersContiguous; - OMX_U32 nBufferAlignment; -} OMX_PARAM_PORTDEFINITIONTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_U32TYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nU32; /**< U32 value */ -} OMX_PARAM_U32TYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONPOLICYTYPE { - OMX_SuspensionDisabled, /**< No suspension; v1.0 behavior */ - OMX_SuspensionEnabled, /**< Suspension allowed */ - OMX_SuspensionPolicyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionPolicyStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspensionPolicyMax = 0x7fffffff -} OMX_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONPOLICYTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONPOLICYTYPE ePolicy; -} OMX_PARAM_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONTYPE { - OMX_NotSuspended, /**< component is not suspended */ - OMX_Suspended, /**< component is suspended */ - OMX_SuspensionKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspendMax = 0x7FFFFFFF -} OMX_SUSPENSIONTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONTYPE eType; -} OMX_PARAM_SUSPENSIONTYPE ; - -typedef struct OMX_CONFIG_BOOLEANTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bEnabled; -} OMX_CONFIG_BOOLEANTYPE; - -/* Parameter specifying the content uri to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTURITYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes, including - actual URI name */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 contentURI[1]; /**< The URI name */ -} OMX_PARAM_CONTENTURITYPE; - -/* Parameter specifying the pipe to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTPIPETYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_HANDLETYPE hPipe; /**< The pipe handle*/ -} OMX_PARAM_CONTENTPIPETYPE; - -/** @ingroup rpm */ -typedef struct OMX_RESOURCECONCEALMENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bResourceConcealmentForbidden; /**< disallow the use of resource concealment - methods (like degrading algorithm quality to - lower resource consumption or functional bypass) - on a component as a resolution to resource conflicts. */ -} OMX_RESOURCECONCEALMENTTYPE; - - -/** @ingroup metadata */ -typedef enum OMX_METADATACHARSETTYPE { - OMX_MetadataCharsetUnknown = 0, - OMX_MetadataCharsetASCII, - OMX_MetadataCharsetBinary, - OMX_MetadataCharsetCodePage1252, - OMX_MetadataCharsetUTF8, - OMX_MetadataCharsetJavaConformantUTF8, - OMX_MetadataCharsetUTF7, - OMX_MetadataCharsetImapUTF7, - OMX_MetadataCharsetUTF16LE, - OMX_MetadataCharsetUTF16BE, - OMX_MetadataCharsetGB12345, - OMX_MetadataCharsetHZGB2312, - OMX_MetadataCharsetGB2312, - OMX_MetadataCharsetGB18030, - OMX_MetadataCharsetGBK, - OMX_MetadataCharsetBig5, - OMX_MetadataCharsetISO88591, - OMX_MetadataCharsetISO88592, - OMX_MetadataCharsetISO88593, - OMX_MetadataCharsetISO88594, - OMX_MetadataCharsetISO88595, - OMX_MetadataCharsetISO88596, - OMX_MetadataCharsetISO88597, - OMX_MetadataCharsetISO88598, - OMX_MetadataCharsetISO88599, - OMX_MetadataCharsetISO885910, - OMX_MetadataCharsetISO885913, - OMX_MetadataCharsetISO885914, - OMX_MetadataCharsetISO885915, - OMX_MetadataCharsetShiftJIS, - OMX_MetadataCharsetISO2022JP, - OMX_MetadataCharsetISO2022JP1, - OMX_MetadataCharsetISOEUCJP, - OMX_MetadataCharsetSMS7Bit, - OMX_MetadataCharsetKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataCharsetVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataCharsetTypeMax= 0x7FFFFFFF -} OMX_METADATACHARSETTYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASCOPETYPE -{ - OMX_MetadataScopeAllLevels, - OMX_MetadataScopeTopLevel, - OMX_MetadataScopePortLevel, - OMX_MetadataScopeNodeLevel, - OMX_MetadataScopeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataScopeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataScopeTypeMax = 0x7fffffff -} OMX_METADATASCOPETYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASEARCHMODETYPE -{ - OMX_MetadataSearchValueSizeByIndex, - OMX_MetadataSearchItemByIndex, - OMX_MetadataSearchNextItemByKey, - OMX_MetadataSearchKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataSearchVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataSearchTypeMax = 0x7fffffff -} OMX_METADATASEARCHMODETYPE; -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMCOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemCount; -} OMX_CONFIG_METADATAITEMCOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemIndex; - OMX_METADATASEARCHMODETYPE eSearchMode; - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U8 nKeySizeUsed; - OMX_U8 nKey[128]; - OMX_METADATACHARSETTYPE eValueCharset; - OMX_STRING sLanguageCountry; - OMX_U32 nValueMaxSize; - OMX_U32 nValueSizeUsed; - OMX_U8 nValue[1]; -} OMX_CONFIG_METADATAITEMTYPE; - -/* @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODECOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNumNodes; -} OMX_CONFIG_CONTAINERNODECOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODEIDTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNodeIndex; - OMX_U32 nNodeID; - OMX_STRING cNodeName; - OMX_BOOL bIsLeafType; -} OMX_CONFIG_CONTAINERNODEIDTYPE; - -/** @ingroup metadata */ -typedef struct OMX_PARAM_METADATAFILTERTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; /* if true then this structure refers to all keys and - * the three key fields below are ignored */ - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U32 nKeySizeUsed; - OMX_U8 nKey [128]; - OMX_U32 nLanguageCountrySizeUsed; - OMX_U8 nLanguageCountry[128]; - OMX_BOOL bEnabled; /* if true then key is part of filter (e.g. - * retained for query later). If false then - * key is not part of filter */ -} OMX_PARAM_METADATAFILTERTYPE; - -/** The OMX_HANDLETYPE structure defines the component handle. The component - * handle is used to access all of the component's public methods and also - * contains pointers to the component's private data area. The component - * handle is initialized by the OMX core (with help from the component) - * during the process of loading the component. After the component is - * successfully loaded, the application can safely access any of the - * component's public functions (although some may return an error because - * the state is inappropriate for the access). - * - * @ingroup comp - */ -typedef struct OMX_COMPONENTTYPE -{ - /** The size of this structure, in bytes. It is the responsibility - of the allocator of this structure to fill in this value. Since - this structure is allocated by the GetHandle function, this - function will fill in this value. */ - OMX_U32 nSize; - - /** nVersion is the version of the OMX specification that the structure - is built against. It is the responsibility of the creator of this - structure to initialize this value and every user of this structure - should verify that it knows how to use the exact version of - this structure found herein. */ - OMX_VERSIONTYPE nVersion; - - /** pComponentPrivate is a pointer to the component private data area. - This member is allocated and initialized by the component when the - component is first loaded. The application should not access this - data area. */ - OMX_PTR pComponentPrivate; - - /** pApplicationPrivate is a pointer that is a parameter to the - OMX_GetHandle method, and contains an application private value - provided by the IL client. This application private data is - returned to the IL Client by OMX in all callbacks */ - OMX_PTR pApplicationPrivate; - - /** refer to OMX_GetComponentVersion in OMX_core.h or the OMX IL - specification for details on the GetComponentVersion method. - */ - OMX_ERRORTYPE (*GetComponentVersion)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STRING pComponentName, - OMX_OUT OMX_VERSIONTYPE* pComponentVersion, - OMX_OUT OMX_VERSIONTYPE* pSpecVersion, - OMX_OUT OMX_UUIDTYPE* pComponentUUID); - - /** refer to OMX_SendCommand in OMX_core.h or the OMX IL - specification for details on the SendCommand method. - */ - OMX_ERRORTYPE (*SendCommand)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_COMMANDTYPE Cmd, - OMX_IN OMX_U32 nParam1, - OMX_IN OMX_PTR pCmdData); - - /** refer to OMX_GetParameter in OMX_core.h or the OMX IL - specification for details on the GetParameter method. - */ - OMX_ERRORTYPE (*GetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nParamIndex, - OMX_INOUT OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_SetParameter in OMX_core.h or the OMX IL - specification for details on the SetParameter method. - */ - OMX_ERRORTYPE (*SetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_GetConfig in OMX_core.h or the OMX IL - specification for details on the GetConfig method. - */ - OMX_ERRORTYPE (*GetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_INOUT OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_SetConfig in OMX_core.h or the OMX IL - specification for details on the SetConfig method. - */ - OMX_ERRORTYPE (*SetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_GetExtensionIndex in OMX_core.h or the OMX IL - specification for details on the GetExtensionIndex method. - */ - OMX_ERRORTYPE (*GetExtensionIndex)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_STRING cParameterName, - OMX_OUT OMX_INDEXTYPE* pIndexType); - - - /** refer to OMX_GetState in OMX_core.h or the OMX IL - specification for details on the GetState method. - */ - OMX_ERRORTYPE (*GetState)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STATETYPE* pState); - - - /** The ComponentTunnelRequest method will interact with another OMX - component to determine if tunneling is possible and to setup the - tunneling. The return codes for this method can be used to - determine if tunneling is not possible, or if tunneling is not - supported. - - Base profile components (i.e. non-interop) do not support this - method and should return OMX_ErrorNotImplemented - - The interop profile component MUST support tunneling to another - interop profile component with a compatible port parameters. - A component may also support proprietary communication. - - If proprietary communication is supported the negotiation of - proprietary communication is done outside of OMX in a vendor - specific way. It is only required that the proper result be - returned and the details of how the setup is done is left - to the component implementation. - - When this method is invoked when nPort in an output port, the - component will: - 1. Populate the pTunnelSetup structure with the output port's - requirements and constraints for the tunnel. - - When this method is invoked when nPort in an input port, the - component will: - 1. Query the necessary parameters from the output port to - determine if the ports are compatible for tunneling - 2. If the ports are compatible, the component should store - the tunnel step provided by the output port - 3. Determine which port (either input or output) is the buffer - supplier, and call OMX_SetParameter on the output port to - indicate this selection. - - The component will return from this call within 5 msec. - - @param [in] hComp - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle method. - @param [in] nPort - nPort is used to select the port on the component to be used - for tunneling. - @param [in] hTunneledComp - Handle of the component to tunnel with. This is the component - handle returned by the call to the OMX_GetHandle method. When - this parameter is 0x0 the component should setup the port for - communication with the application / IL Client. - @param [in] nPortOutput - nPortOutput is used indicate the port the component should - tunnel with. - @param [in] pTunnelSetup - Pointer to the tunnel setup structure. When nPort is an output port - the component should populate the fields of this structure. When - When nPort is an input port the component should review the setup - provided by the component with the output port. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup tun - */ - - OMX_ERRORTYPE (*ComponentTunnelRequest)( - OMX_IN OMX_HANDLETYPE hComp, - OMX_IN OMX_U32 nPort, - OMX_IN OMX_HANDLETYPE hTunneledComp, - OMX_IN OMX_U32 nTunneledPort, - OMX_INOUT OMX_TUNNELSETUPTYPE* pTunnelSetup); - - /** refer to OMX_UseBuffer in OMX_core.h or the OMX IL - specification for details on the UseBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*UseBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes, - OMX_IN OMX_U8* pBuffer); - - /** refer to OMX_AllocateBuffer in OMX_core.h or the OMX IL - specification for details on the AllocateBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*AllocateBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBuffer, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes); - - /** refer to OMX_FreeBuffer in OMX_core.h or the OMX IL - specification for details on the FreeBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FreeBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_EmptyThisBuffer in OMX_core.h or the OMX IL - specification for details on the EmptyThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_FillThisBuffer in OMX_core.h or the OMX IL - specification for details on the FillThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FillThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The SetCallbacks method is used by the core to specify the callback - structure from the application to the component. This is a blocking - call. The component will return from this call within 5 msec. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] pCallbacks - pointer to an OMX_CALLBACKTYPE structure used to provide the - callback information to the component - @param [in] pAppData - pointer to an application defined value. It is anticipated that - the application will pass a pointer to a data structure or a "this - pointer" in this area to allow the callback (in the application) - to determine the context of the call - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*SetCallbacks)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_CALLBACKTYPE* pCallbacks, - OMX_IN OMX_PTR pAppData); - - /** ComponentDeInit method is used to deinitialize the component - providing a means to free any resources allocated at component - initialization. NOTE: After this call the component handle is - not valid for further use. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*ComponentDeInit)( - OMX_IN OMX_HANDLETYPE hComponent); - - /** @ingroup buf */ - OMX_ERRORTYPE (*UseEGLImage)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN void* eglImage); - - OMX_ERRORTYPE (*ComponentRoleEnum)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_U8 *cRole, - OMX_IN OMX_U32 nIndex); - -} OMX_COMPONENTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_ContentPipe.h b/third_party/openmax/include/OMX_ContentPipe.h deleted file mode 100644 index 5f6310c28a..0000000000 --- a/third_party/openmax/include/OMX_ContentPipe.h +++ /dev/null @@ -1,195 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_ContentPipe.h - OpenMax IL version 1.1.2 - * The OMX_ContentPipe header file contains the definitions used to define - * the public interface for content piples. This header file is intended to - * be used by the component. - */ - -#ifndef OMX_CONTENTPIPE_H -#define OMX_CONTENTPIPE_H - -#ifndef KD_EACCES -/* OpenKODE error codes. CPResult values may be zero (indicating success - or one of the following values) */ -#define KD_EACCES (1) -#define KD_EADDRINUSE (2) -#define KD_EAGAIN (5) -#define KD_EBADF (7) -#define KD_EBUSY (8) -#define KD_ECONNREFUSED (9) -#define KD_ECONNRESET (10) -#define KD_EDEADLK (11) -#define KD_EDESTADDRREQ (12) -#define KD_ERANGE (35) -#define KD_EEXIST (13) -#define KD_EFBIG (14) -#define KD_EHOSTUNREACH (15) -#define KD_EINVAL (17) -#define KD_EIO (18) -#define KD_EISCONN (20) -#define KD_EISDIR (21) -#define KD_EMFILE (22) -#define KD_ENAMETOOLONG (23) -#define KD_ENOENT (24) -#define KD_ENOMEM (25) -#define KD_ENOSPC (26) -#define KD_ENOSYS (27) -#define KD_ENOTCONN (28) -#define KD_EPERM (33) -#define KD_ETIMEDOUT (36) -#define KD_EILSEQ (19) -#endif - -/** Map types from OMX standard types only here so interface is as generic as possible. */ -typedef OMX_U32 CPresult; -typedef char * CPstring; -typedef void * CPhandle; -typedef OMX_U32 CPuint; -typedef OMX_S32 CPint; -typedef char CPbyte; -typedef OMX_BOOL CPbool; - -/** enumeration of origin types used in the CP_PIPETYPE's Seek function - * @ingroup cp - */ -typedef enum CP_ORIGINTYPE { - CP_OriginBegin, - CP_OriginCur, - CP_OriginEnd, - CP_OriginKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_OriginVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_OriginMax = 0X7FFFFFFF -} CP_ORIGINTYPE; - -/** enumeration of contact access types used in the CP_PIPETYPE's Open function - * @ingroup cp - */ -typedef enum CP_ACCESSTYPE { - CP_AccessRead, - CP_AccessWrite, - CP_AccessReadWrite , - CP_AccessKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_AccessVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_AccessMax = 0X7FFFFFFF -} CP_ACCESSTYPE; - -/** enumeration of results returned by the CP_PIPETYPE's CheckAvailableBytes function - * @ingroup cp - */ -typedef enum CP_CHECKBYTESRESULTTYPE -{ - CP_CheckBytesOk, /**< There are at least the request number - of bytes available */ - CP_CheckBytesNotReady, /**< The pipe is still retrieving bytes - and presently lacks sufficient bytes. - Client will be called when they are - sufficient bytes are available. */ - CP_CheckBytesInsufficientBytes , /**< The pipe has retrieved all bytes - but those available are less than those - requested */ - CP_CheckBytesAtEndOfStream, /**< The pipe has reached the end of stream - and no more bytes are available. */ - CP_CheckBytesOutOfBuffers, /**< All read/write buffers are currently in use. */ - CP_CheckBytesKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_CheckBytesVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_CheckBytesMax = 0X7FFFFFFF -} CP_CHECKBYTESRESULTTYPE; - -/** enumeration of content pipe events sent to the client callback. - * @ingroup cp - */ -typedef enum CP_EVENTTYPE{ - CP_BytesAvailable, /** bytes requested in a CheckAvailableBytes call are now available*/ - CP_Overflow, /** enumeration of content pipe events sent to the client callback*/ - CP_PipeDisconnected , /** enumeration of content pipe events sent to the client callback*/ - CP_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_EventMax = 0X7FFFFFFF -} CP_EVENTTYPE; - -/** content pipe definition - * @ingroup cp - */ -typedef struct CP_PIPETYPE -{ - /** Open a content stream for reading or writing. */ - CPresult (*Open)( CPhandle* hContent, CPstring szURI, CP_ACCESSTYPE eAccess ); - - /** Close a content stream. */ - CPresult (*Close)( CPhandle hContent ); - - /** Create a content source and open it for writing. */ - CPresult (*Create)( CPhandle *hContent, CPstring szURI ); - - /** Check the that specified number of bytes are available for reading or writing (depending on access type).*/ - CPresult (*CheckAvailableBytes)( CPhandle hContent, CPuint nBytesRequested, CP_CHECKBYTESRESULTTYPE *eResult ); - - /** Seek to certain position in the content relative to the specified origin. */ - CPresult (*SetPosition)( CPhandle hContent, CPint nOffset, CP_ORIGINTYPE eOrigin); - - /** Retrieve the current position relative to the start of the content. */ - CPresult (*GetPosition)( CPhandle hContent, CPuint *pPosition); - - /** Retrieve data of the specified size from the content stream (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency reads. */ - CPresult (*Read)( CPhandle hContent, CPbyte *pData, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe that contains the requested number of bytes. - Buffer contains the next block of bytes, as specified by nSize, of the content. nSize also - returns the size of the block actually read. Content pointer advances the by the returned size. - Note: pipe provides pointer. This function is appropriate for large reads. The client must call - ReleaseReadBuffer when done with buffer. - - In some cases the requested block may not reside in contiguous memory within the - pipe implementation. For instance if the pipe leverages a circular buffer then the requested - block may straddle the boundary of the circular buffer. By default a pipe implementation - performs a copy in this case to provide the block to the pipe client in one contiguous buffer. - If, however, the client sets bForbidCopy, then the pipe returns only those bytes preceding the memory - boundary. Here the client may retrieve the data in segments over successive calls. */ - CPresult (*ReadBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint *nSize, CPbool bForbidCopy); - - /** Release a buffer obtained by ReadBuffer back to the pipe. */ - CPresult (*ReleaseReadBuffer)(CPhandle hContent, CPbyte *pBuffer); - - /** Write data of the specified size to the content (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency writes. */ - CPresult (*Write)( CPhandle hContent, CPbyte *data, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe used to write data to the content. - Client will fill buffer with output data. Note: pipe provides pointer. This function is appropriate - for large writes. The client must call WriteBuffer when done it has filled the buffer with data.*/ - CPresult (*GetWriteBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint nSize); - - /** Deliver a buffer obtained via GetWriteBuffer to the pipe. Pipe will write the - the contents of the buffer to content and advance content pointer by the size of the buffer */ - CPresult (*WriteBuffer)( CPhandle hContent, CPbyte *pBuffer, CPuint nFilledSize); - - /** Register a per-handle client callback with the content pipe. */ - CPresult (*RegisterCallback)( CPhandle hContent, CPresult (*ClientCallback)(CP_EVENTTYPE eEvent, CPuint iParam)); - -} CP_PIPETYPE; - -#endif - diff --git a/third_party/openmax/include/OMX_Core.h b/third_party/openmax/include/OMX_Core.h deleted file mode 100644 index 52d211f0dc..0000000000 --- a/third_party/openmax/include/OMX_Core.h +++ /dev/null @@ -1,1440 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Core.h - OpenMax IL version 1.1.2 - * The OMX_Core header file contains the definitions used by both the - * application and the component to access common items. - */ - -#ifndef OMX_Core_h -#define OMX_Core_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** The OMX_COMMANDTYPE enumeration is used to specify the action in the - * OMX_SendCommand macro. - * @ingroup core - */ -typedef enum OMX_COMMANDTYPE -{ - OMX_CommandStateSet, /**< Change the component state */ - OMX_CommandFlush, /**< Flush the data queue(s) of a component */ - OMX_CommandPortDisable, /**< Disable a port on a component. */ - OMX_CommandPortEnable, /**< Enable a port on a component. */ - OMX_CommandMarkBuffer, /**< Mark a component/buffer for observation */ - OMX_CommandKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_CommandVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_CommandMax = 0X7FFFFFFF -} OMX_COMMANDTYPE; - - - -/** The OMX_STATETYPE enumeration is used to indicate or change the component - * state. This enumeration reflects the current state of the component when - * used with the OMX_GetState macro or becomes the parameter in a state change - * command when used with the OMX_SendCommand macro. - * - * The component will be in the Loaded state after the component is initially - * loaded into memory. In the Loaded state, the component is not allowed to - * allocate or hold resources other than to build it's internal parameter - * and configuration tables. The application will send one or more - * SetParameters/GetParameters and SetConfig/GetConfig commands to the - * component and the component will record each of these parameter and - * configuration changes for use later. When the application sends the - * Idle command, the component will acquire the resources needed for the - * specified configuration and will transition to the idle state if the - * allocation is successful. If the component cannot successfully - * transition to the idle state for any reason, the state of the component - * shall be fully rolled back to the Loaded state (e.g. all allocated - * resources shall be released). When the component receives the command - * to go to the Executing state, it shall begin processing buffers by - * sending all input buffers it holds to the application. While - * the component is in the Idle state, the application may also send the - * Pause command. If the component receives the pause command while in the - * Idle state, the component shall send all input buffers it holds to the - * application, but shall not begin processing buffers. This will allow the - * application to prefill buffers. - * - * @ingroup comp - */ - -typedef enum OMX_STATETYPE -{ - OMX_StateInvalid, /**< component has detected that it's internal data - structures are corrupted to the point that - it cannot determine it's state properly */ - OMX_StateLoaded, /**< component has been loaded but has not completed - initialization. The OMX_SetParameter macro - and the OMX_GetParameter macro are the only - valid macros allowed to be sent to the - component in this state. */ - OMX_StateIdle, /**< component initialization has been completed - successfully and the component is ready to - to start. */ - OMX_StateExecuting, /**< component has accepted the start command and - is processing data (if data is available) */ - OMX_StatePause, /**< component has received pause command */ - OMX_StateWaitForResources, /**< component is waiting for resources, either after - preemption or before it gets the resources requested. - See specification for complete details. */ - OMX_StateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_StateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_StateMax = 0X7FFFFFFF -} OMX_STATETYPE; - -/** The OMX_ERRORTYPE enumeration defines the standard OMX Errors. These - * errors should cover most of the common failure cases. However, - * vendors are free to add additional error messages of their own as - * long as they follow these rules: - * 1. Vendor error messages shall be in the range of 0x90000000 to - * 0x9000FFFF. - * 2. Vendor error messages shall be defined in a header file provided - * with the component. No error messages are allowed that are - * not defined. - */ -typedef enum OMX_ERRORTYPE -{ - OMX_ErrorNone = 0, - - /** There were insufficient resources to perform the requested operation */ - OMX_ErrorInsufficientResources = (OMX_S32) 0x80001000, - - /** There was an error, but the cause of the error could not be determined */ - OMX_ErrorUndefined = (OMX_S32) 0x80001001, - - /** The component name string was not valid */ - OMX_ErrorInvalidComponentName = (OMX_S32) 0x80001002, - - /** No component with the specified name string was found */ - OMX_ErrorComponentNotFound = (OMX_S32) 0x80001003, - - /** The component specified did not have a "OMX_ComponentInit" or - "OMX_ComponentDeInit entry point */ - OMX_ErrorInvalidComponent = (OMX_S32) 0x80001004, - - /** One or more parameters were not valid */ - OMX_ErrorBadParameter = (OMX_S32) 0x80001005, - - /** The requested function is not implemented */ - OMX_ErrorNotImplemented = (OMX_S32) 0x80001006, - - /** The buffer was emptied before the next buffer was ready */ - OMX_ErrorUnderflow = (OMX_S32) 0x80001007, - - /** The buffer was not available when it was needed */ - OMX_ErrorOverflow = (OMX_S32) 0x80001008, - - /** The hardware failed to respond as expected */ - OMX_ErrorHardware = (OMX_S32) 0x80001009, - - /** The component is in the state OMX_StateInvalid */ - OMX_ErrorInvalidState = (OMX_S32) 0x8000100A, - - /** Stream is found to be corrupt */ - OMX_ErrorStreamCorrupt = (OMX_S32) 0x8000100B, - - /** Ports being connected are not compatible */ - OMX_ErrorPortsNotCompatible = (OMX_S32) 0x8000100C, - - /** Resources allocated to an idle component have been - lost resulting in the component returning to the loaded state */ - OMX_ErrorResourcesLost = (OMX_S32) 0x8000100D, - - /** No more indicies can be enumerated */ - OMX_ErrorNoMore = (OMX_S32) 0x8000100E, - - /** The component detected a version mismatch */ - OMX_ErrorVersionMismatch = (OMX_S32) 0x8000100F, - - /** The component is not ready to return data at this time */ - OMX_ErrorNotReady = (OMX_S32) 0x80001010, - - /** There was a timeout that occurred */ - OMX_ErrorTimeout = (OMX_S32) 0x80001011, - - /** This error occurs when trying to transition into the state you are already in */ - OMX_ErrorSameState = (OMX_S32) 0x80001012, - - /** Resources allocated to an executing or paused component have been - preempted, causing the component to return to the idle state */ - OMX_ErrorResourcesPreempted = (OMX_S32) 0x80001013, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the allocation of buffers (on a transition from the LOADED to the IDLE state or - on a port restart) when it deems that it has waited an unusually long time for the supplier - to send it an allocated buffer via a UseBuffer call. */ - OMX_ErrorPortUnresponsiveDuringAllocation = (OMX_S32) 0x80001014, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the deallocation of buffers (on a transition from the IDLE to LOADED state or - on a port stop) when it deems that it has waited an unusually long time for the supplier - to request the deallocation of a buffer header via a FreeBuffer call. */ - OMX_ErrorPortUnresponsiveDuringDeallocation = (OMX_S32) 0x80001015, - - /** A supplier port sends this error to the IL client (via the EventHandler callback) - during the stopping of a port (either on a transition from the IDLE to LOADED - state or a port stop) when it deems that it has waited an unusually long time for - the non-supplier to return a buffer via an EmptyThisBuffer or FillThisBuffer call. */ - OMX_ErrorPortUnresponsiveDuringStop = (OMX_S32) 0x80001016, - - /** Attempting a state transtion that is not allowed */ - OMX_ErrorIncorrectStateTransition = (OMX_S32) 0x80001017, - - /* Attempting a command that is not allowed during the present state. */ - OMX_ErrorIncorrectStateOperation = (OMX_S32) 0x80001018, - - /** The values encapsulated in the parameter or config structure are not supported. */ - OMX_ErrorUnsupportedSetting = (OMX_S32) 0x80001019, - - /** The parameter or config indicated by the given index is not supported. */ - OMX_ErrorUnsupportedIndex = (OMX_S32) 0x8000101A, - - /** The port index supplied is incorrect. */ - OMX_ErrorBadPortIndex = (OMX_S32) 0x8000101B, - - /** The port has lost one or more of its buffers and it thus unpopulated. */ - OMX_ErrorPortUnpopulated = (OMX_S32) 0x8000101C, - - /** Component suspended due to temporary loss of resources */ - OMX_ErrorComponentSuspended = (OMX_S32) 0x8000101D, - - /** Component suspended due to an inability to acquire dynamic resources */ - OMX_ErrorDynamicResourcesUnavailable = (OMX_S32) 0x8000101E, - - /** When the macroblock error reporting is enabled the component returns new error - for every frame that has errors */ - OMX_ErrorMbErrorsInFrame = (OMX_S32) 0x8000101F, - - /** A component reports this error when it cannot parse or determine the format of an input stream. */ - OMX_ErrorFormatNotDetected = (OMX_S32) 0x80001020, - - /** The content open operation failed. */ - OMX_ErrorContentPipeOpenFailed = (OMX_S32) 0x80001021, - - /** The content creation operation failed. */ - OMX_ErrorContentPipeCreationFailed = (OMX_S32) 0x80001022, - - /** Separate table information is being used */ - OMX_ErrorSeperateTablesUsed = (OMX_S32) 0x80001023, - - /** Tunneling is unsupported by the component*/ - OMX_ErrorTunnelingUnsupported = (OMX_S32) 0x80001024, - - OMX_ErrorKhronosExtensions = (OMX_S32)0x8F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ErrorVendorStartUnused = (OMX_S32)0x90000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ErrorMax = 0x7FFFFFFF -} OMX_ERRORTYPE; - -/** @ingroup core */ -typedef OMX_ERRORTYPE (* OMX_COMPONENTINITTYPE)(OMX_IN OMX_HANDLETYPE hComponent); - -/** @ingroup core */ -typedef struct OMX_COMPONENTREGISTERTYPE -{ - const char * pName; /* Component name, 128 byte limit (including '\0') applies */ - OMX_COMPONENTINITTYPE pInitialize; /* Component instance initialization function */ -} OMX_COMPONENTREGISTERTYPE; - -/** @ingroup core */ -extern OMX_COMPONENTREGISTERTYPE OMX_ComponentRegistered[]; - -/** @ingroup rpm */ -typedef struct OMX_PRIORITYMGMTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nGroupPriority; /**< Priority of the component group */ - OMX_U32 nGroupID; /**< ID of the component group */ -} OMX_PRIORITYMGMTTYPE; - -/* Component name and Role names are limited to 128 characters including the terminating '\0'. */ -#define OMX_MAX_STRINGNAME_SIZE 128 - -/** @ingroup comp */ -typedef struct OMX_PARAM_COMPONENTROLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 cRole[OMX_MAX_STRINGNAME_SIZE]; /**< name of standard component which defines component role */ -} OMX_PARAM_COMPONENTROLETYPE; - -/** End of Stream Buffer Flag: - * - * A component sets EOS when it has no more data to emit on a particular - * output port. Thus an output port shall set EOS on the last buffer it - * emits. A component's determination of when an output port should - * cease sending data is implemenation specific. - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_EOS 0x00000001 - -/** Start Time Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the STARTTIME - * flag on the buffer that contains the starting timestamp for the - * stream. The starting timestamp corresponds to the first data that - * should be displayed at startup or after a seek. - * The first timestamp of the stream is not necessarily the start time. - * For instance, in the case of a seek to a particular video frame, - * the target frame may be an interframe. Thus the first buffer of - * the stream will be the intra-frame preceding the target frame and - * the starttime will occur with the target frame (with any other - * required frames required to reconstruct the target intervening). - * - * The STARTTIME flag is directly associated with the buffer's - * timestamp ' thus its association to buffer data and its - * propagation is identical to the timestamp's. - * - * When a Sync Component client receives a buffer with the - * STARTTIME flag it shall perform a SetConfig on its sync port - * using OMX_ConfigTimeClientStartTime and passing the buffer's - * timestamp. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_STARTTIME 0x00000002 - - - -/** Decode Only Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the DECODEONLY - * flag on any buffer that should shall be decoded but should not be - * displayed. This flag is used, for instance, when a source seeks to - * a target interframe that requires the decode of frames preceding the - * target to facilitate the target's reconstruction. In this case the - * source would emit the frames preceding the target downstream - * but mark them as decode only. - * - * The DECODEONLY is associated with buffer data and propagated in a - * manner identical to the buffer timestamp. - * - * A component that renders data should ignore all buffers with - * the DECODEONLY flag set. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DECODEONLY 0x00000004 - - -/* Data Corrupt Flag: This flag is set when the IL client believes the data in the associated buffer is corrupt - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DATACORRUPT 0x00000008 - -/* End of Frame: The buffer contains exactly one end of frame and no data - * occurs after the end of frame. This flag is an optional hint. The absence - * of this flag does not imply the absence of an end of frame within the buffer. - * @ingroup buf -*/ -#define OMX_BUFFERFLAG_ENDOFFRAME 0x00000010 - -/* Sync Frame Flag: This flag is set when the buffer content contains a coded sync frame ' - * a frame that has no dependency on any other frame information - * @ingroup buf - */ -#define OMX_BUFFERFLAG_SYNCFRAME 0x00000020 - -/* Extra data present flag: there is extra data appended to the data stream - * residing in the buffer - * @ingroup buf - */ -#define OMX_BUFFERFLAG_EXTRADATA 0x00000040 - -/** Codec Config Buffer Flag: -* OMX_BUFFERFLAG_CODECCONFIG is an optional flag that is set by an -* output port when all bytes in the buffer form part or all of a set of -* codec specific configuration data. Examples include SPS/PPS nal units -* for OMX_VIDEO_CodingAVC or AudioSpecificConfig data for -* OMX_AUDIO_CodingAAC. Any component that for a given stream sets -* OMX_BUFFERFLAG_CODECCONFIG shall not mix codec configuration bytes -* with frame data in the same buffer, and shall send all buffers -* containing codec configuration bytes before any buffers containing -* frame data that those configurations bytes describe. -* If the stream format for a particular codec has a frame specific -* header at the start of each frame, for example OMX_AUDIO_CodingMP3 or -* OMX_AUDIO_CodingAAC in ADTS mode, then these shall be presented as -* normal without setting OMX_BUFFERFLAG_CODECCONFIG. - * @ingroup buf - */ -#define OMX_BUFFERFLAG_CODECCONFIG 0x00000080 - -/* -* OMX_BUFFERFLAG_READONLY: This flag is set when a component emitting the -* buffer on an output port or the IL client wishes to identify the buffer -* payload contents to be read-only. An IL client or an input port -* shall not alter the contents of the buffer. This flag shall only be -* cleared by the originator of the buffer when the buffer is returned. -* For tunneled ports, the usage of this flag shall be allowed only if the -* components negotiated a read-only tunnel -*/ -#define OMX_BUFFERFLAG_READONLY 0x00000200 - -/** @ingroup buf */ -typedef struct OMX_BUFFERHEADERTYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8* pBuffer; /**< Pointer to actual block of memory - that is acting as the buffer */ - OMX_U32 nAllocLen; /**< size of the buffer allocated, in bytes */ - OMX_U32 nFilledLen; /**< number of bytes currently in the - buffer */ - OMX_U32 nOffset; /**< start offset of valid data in bytes from - the start of the buffer */ - OMX_PTR pAppPrivate; /**< pointer to any data the application - wants to associate with this buffer */ - OMX_PTR pPlatformPrivate; /**< pointer to any data the platform - wants to associate with this buffer */ - OMX_PTR pInputPortPrivate; /**< pointer to any data the input port - wants to associate with this buffer */ - OMX_PTR pOutputPortPrivate; /**< pointer to any data the output port - wants to associate with this buffer */ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will generate a - mark event upon processing this buffer. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ - OMX_U32 nTickCount; /**< Optional entry that the component and - application can update with a tick count - when they access the component. This - value should be in microseconds. Since - this is a value relative to an arbitrary - starting point, this value cannot be used - to determine absolute time. This is an - optional entry and not all components - will update it.*/ - OMX_TICKS nTimeStamp; /**< Timestamp corresponding to the sample - starting at the first logical sample - boundary in the buffer. Timestamps of - successive samples within the buffer may - be inferred by adding the duration of the - of the preceding buffer to the timestamp - of the preceding buffer.*/ - OMX_U32 nFlags; /**< buffer specific flags */ - OMX_U32 nOutputPortIndex; /**< The index of the output port (if any) using - this buffer */ - OMX_U32 nInputPortIndex; /**< The index of the input port (if any) using - this buffer */ -} OMX_BUFFERHEADERTYPE; - -/** The OMX_EXTRADATATYPE enumeration is used to define the - * possible extra data payload types. - * NB: this enum is binary backwards compatible with the previous - * OMX_EXTRADATA_QUANT define. This should be replaced with - * OMX_ExtraDataQuantization. - */ -typedef enum OMX_EXTRADATATYPE -{ - OMX_ExtraDataNone = 0, /**< Indicates that no more extra data sections follow */ - OMX_ExtraDataQuantization, /**< The data payload contains quantization data */ - OMX_ExtraDataKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ExtraDataVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ExtraDataMax = 0x7FFFFFFF -} OMX_EXTRADATATYPE; - - -typedef struct OMX_OTHER_EXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_EXTRADATATYPE eType; /* Extra Data type */ - OMX_U32 nDataSize; /* Size of the supporting data to follow */ - OMX_U8 data[1]; /* Supporting data hint */ -} OMX_OTHER_EXTRADATATYPE; - -/** @ingroup comp */ -typedef struct OMX_PORT_PARAM_TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPorts; /**< The number of ports for this component */ - OMX_U32 nStartPortNumber; /** first port number for this type of port */ -} OMX_PORT_PARAM_TYPE; - -/** @ingroup comp */ -typedef enum OMX_EVENTTYPE -{ - OMX_EventCmdComplete, /**< component has sucessfully completed a command */ - OMX_EventError, /**< component has detected an error condition */ - OMX_EventMark, /**< component has detected a buffer mark */ - OMX_EventPortSettingsChanged, /**< component is reported a port settings change */ - OMX_EventBufferFlag, /**< component has detected an EOS */ - OMX_EventResourcesAcquired, /**< component has been granted resources and is - automatically starting the state change from - OMX_StateWaitForResources to OMX_StateIdle. */ - OMX_EventComponentResumed, /**< Component resumed due to reacquisition of resources */ - OMX_EventDynamicResourcesAvailable, /**< Component has acquired previously unavailable dynamic resources */ - OMX_EventPortFormatDetected, /**< Component has detected a supported format. */ - OMX_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_EventMax = 0x7FFFFFFF -} OMX_EVENTTYPE; - -typedef struct OMX_CALLBACKTYPE -{ - /** The EventHandler method is used to notify the application when an - event of interest occurs. Events are defined in the OMX_EVENTTYPE - enumeration. Please see that enumeration for details of what will - be returned for each type of event. Callbacks should not return - an error to the component, so if an error occurs, the application - shall handle it internally. This is a blocking call. - - The application should return from this call within 5 msec to avoid - blocking the component for an excessively long period of time. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param eEvent - Event that the component wants to notify the application about. - @param nData1 - nData will be the OMX_ERRORTYPE for an error event and will be - an OMX_COMMANDTYPE for a command complete event and OMX_INDEXTYPE for a OMX_PortSettingsChanged event. - @param nData2 - nData2 will hold further information related to the event. Can be OMX_STATETYPE for - a OMX_CommandStateSet command or port index for a OMX_PortSettingsChanged event. - Default value is 0 if not used. ) - @param pEventData - Pointer to additional event-specific data (see spec for meaning). - */ - - OMX_ERRORTYPE (*EventHandler)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_EVENTTYPE eEvent, - OMX_IN OMX_U32 nData1, - OMX_IN OMX_U32 nData2, - OMX_IN OMX_PTR pEventData); - - /** The EmptyBufferDone method is used to return emptied buffers from an - input port back to the application for reuse. This is a blocking call - so the application should not attempt to refill the buffers during this - call, but should queue them and refill them in another thread. There - is no error return, so the application shall handle any errors generated - internally. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was emptied. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyBufferDone)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The FillBufferDone method is used to return filled buffers from an - output port back to the application for emptying and then reuse. - This is a blocking call so the application should not attempt to - empty the buffers during this call, but should queue the buffers - and empty them in another thread. There is no error return, so - the application shall handle any errors generated internally. The - application shall also update the buffer header to indicate the - number of bytes placed into the buffer. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was filled. - @ingroup buf - */ - OMX_ERRORTYPE (*FillBufferDone)( - OMX_OUT OMX_HANDLETYPE hComponent, - OMX_OUT OMX_PTR pAppData, - OMX_OUT OMX_BUFFERHEADERTYPE* pBuffer); - -} OMX_CALLBACKTYPE; - -/** The OMX_BUFFERSUPPLIERTYPE enumeration is used to dictate port supplier - preference when tunneling between two ports. - @ingroup tun buf -*/ -typedef enum OMX_BUFFERSUPPLIERTYPE -{ - OMX_BufferSupplyUnspecified = 0x0, /**< port supplying the buffers is unspecified, - or don't care */ - OMX_BufferSupplyInput, /**< input port supplies the buffers */ - OMX_BufferSupplyOutput, /**< output port supplies the buffers */ - OMX_BufferSupplyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_BufferSupplyVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_BufferSupplyMax = 0x7FFFFFFF -} OMX_BUFFERSUPPLIERTYPE; - - -/** buffer supplier parameter - * @ingroup tun - */ -typedef struct OMX_PARAM_BUFFERSUPPLIERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BUFFERSUPPLIERTYPE eBufferSupplier; /**< buffer supplier */ -} OMX_PARAM_BUFFERSUPPLIERTYPE; - - -/**< indicates that buffers received by an input port of a tunnel - may not modify the data in the buffers - @ingroup tun - */ -#define OMX_PORTTUNNELFLAG_READONLY 0x00000001 - - -/** The OMX_TUNNELSETUPTYPE structure is used to pass data from an output - port to an input port as part the two ComponentTunnelRequest calls - resulting from a OMX_SetupTunnel call from the IL Client. - @ingroup tun - */ -typedef struct OMX_TUNNELSETUPTYPE -{ - OMX_U32 nTunnelFlags; /**< bit flags for tunneling */ - OMX_BUFFERSUPPLIERTYPE eSupplier; /**< supplier preference */ -} OMX_TUNNELSETUPTYPE; - -/* OMX Component headers is included to enable the core to use - macros for functions into the component for OMX release 1.0. - Developers should not access any structures or data from within - the component header directly */ -/* TO BE REMOVED - #include */ - -/** GetComponentVersion will return information about the component. - This is a blocking call. This macro will go directly from the - application to the component (via a core macro). The - component will return from this call within 5 msec. - @param [in] hComponent - handle of component to execute the command - @param [out] pComponentName - pointer to an empty string of length 128 bytes. The component - will write its name into this string. The name will be - terminated by a single zero byte. The name of a component will - be 127 bytes or less to leave room for the trailing zero byte. - An example of a valid component name is "OMX.ABC.ChannelMixer\0". - @param [out] pComponentVersion - pointer to an OMX Version structure that the component will fill - in. The component will fill in a value that indicates the - component version. NOTE: the component version is NOT the same - as the OMX Specification version (found in all structures). The - component version is defined by the vendor of the component and - its value is entirely up to the component vendor. - @param [out] pSpecVersion - pointer to an OMX Version structure that the component will fill - in. The SpecVersion is the version of the specification that the - component was built against. Please note that this value may or - may not match the structure's version. For example, if the - component was built against the 2.0 specification, but the - application (which creates the structure is built against the - 1.0 specification the versions would be different. - @param [out] pComponentUUID - pointer to the UUID of the component which will be filled in by - the component. The UUID is a unique identifier that is set at - RUN time for the component and is unique to each instantion of - the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) /* Macro End */ - - -/** Send a command to the component. This call is a non-blocking call. - The component should check the parameters and then queue the command - to the component thread to be executed. The component thread shall - send the EventHandler() callback at the conclusion of the command. - This macro will go directly from the application to the component (via - a core macro). The component will return from this call within 5 msec. - - When the command is "OMX_CommandStateSet" the component will queue a - state transition to the new state idenfied in nParam. - - When the command is "OMX_CommandFlush", to flush a port's buffer queues, - the command will force the component to return all buffers NOT CURRENTLY - BEING PROCESSED to the application, in the order in which the buffers - were received. - - When the command is "OMX_CommandPortDisable" or - "OMX_CommandPortEnable", the component's port (given by the value of - nParam) will be stopped or restarted. - - When the command "OMX_CommandMarkBuffer" is used to mark a buffer, the - pCmdData will point to a OMX_MARKTYPE structure containing the component - handle of the component to examine the buffer chain for the mark. nParam1 - contains the index of the port on which the buffer mark is applied. - - Specification text for more details. - - @param [in] hComponent - handle of component to execute the command - @param [in] Cmd - Command for the component to execute - @param [in] nParam - Parameter for the command to be executed. When Cmd has the value - OMX_CommandStateSet, value is a member of OMX_STATETYPE. When Cmd has - the value OMX_CommandFlush, value of nParam indicates which port(s) - to flush. -1 is used to flush all ports a single port index will - only flush that port. When Cmd has the value "OMX_CommandPortDisable" - or "OMX_CommandPortEnable", the component's port is given by - the value of nParam. When Cmd has the value "OMX_CommandMarkBuffer" - the components pot is given by the value of nParam. - @param [in] pCmdData - Parameter pointing to the OMX_MARKTYPE structure when Cmd has the value - "OMX_CommandMarkBuffer". - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) \ - ((OMX_COMPONENTTYPE*)hComponent)->SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) /* Macro End */ - - -/** The OMX_GetParameter macro will get one of the current parameter - settings from the component. This macro cannot only be invoked when - the component is in the OMX_StateInvalid state. The nParamIndex - parameter is used to indicate which structure is being requested from - the component. The application shall allocate the correct structure - and shall fill in the structure size and version information before - invoking this macro. When the parameter applies to a port, the - caller shall fill in the appropriate nPortIndex value indicating the - port on which the parameter applies. If the component has not had - any settings changed, then the component should return a set of - valid DEFAULT parameters for the component. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nParamIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentParameterStructure - Pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_SetParameter macro will send an initialization parameter - structure to a component. Each structure shall be sent one at a time, - in a separate invocation of the macro. This macro can only be - invoked when the component is in the OMX_StateLoaded state, or the - port is disabled (when the parameter applies to a port). The - nParamIndex parameter is used to indicate which structure is being - passed to the component. The application shall allocate the - correct structure and shall fill in the structure size and version - information (as well as the actual data) before invoking this macro. - The application is free to dispose of this structure after the call - as the component is required to copy any data it shall retain. This - is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration. - @param [in] pComponentParameterStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_GetConfig macro will get one of the configuration structures - from a component. This macro can be invoked anytime after the - component has been loaded. The nParamIndex call parameter is used to - indicate which structure is being requested from the component. The - application shall allocate the correct structure and shall fill in the - structure size and version information before invoking this macro. - If the component has not had this configuration parameter sent before, - then the component should return a set of valid DEFAULT values for the - component. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentConfigStructure - pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp -*/ -#define OMX_GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_SetConfig macro will send one of the configuration - structures to a component. Each structure shall be sent one at a time, - each in a separate invocation of the macro. This macro can be invoked - anytime after the component has been loaded. The application shall - allocate the correct structure and shall fill in the structure size - and version information (as well as the actual data) before invoking - this macro. The application is free to dispose of this structure after - the call as the component is required to copy any data it shall retain. - This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nConfigIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration above. - @param [in] pComponentConfigStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_GetExtensionIndex macro will invoke a component to translate - a vendor specific configuration or parameter string into an OMX - structure index. There is no requirement for the vendor to support - this command for the indexes already found in the OMX_INDEXTYPE - enumeration (this is done to save space in small components). The - component shall support all vendor supplied extension indexes not found - in the master OMX_INDEXTYPE enumeration. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] cParameterName - OMX_STRING that shall be less than 128 characters long including - the trailing null byte. This is the string that will get - translated by the component into a configuration index. - @param [out] pIndexType - a pointer to a OMX_INDEXTYPE to receive the index value. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) /* Macro End */ - - -/** The OMX_GetState macro will invoke the component to get the current - state of the component and place the state value into the location - pointed to by pState. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] pState - pointer to the location to receive the state. The value returned - is one of the OMX_STATETYPE members - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetState( \ - hComponent, \ - pState) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetState( \ - hComponent, \ - pState) /* Macro End */ - - -/** The OMX_UseBuffer macro will request that the component use - a buffer (and allocate its own buffer header) already allocated - by another component, or by the IL Client. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ - -#define OMX_UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) - - -/** The OMX_AllocateBuffer macro will request that the component allocate - a new buffer and buffer header. The component will allocate the - buffer and the buffer header and return a pointer to the buffer - header. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive - the pointer to the buffer header - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] nSizeBytes - size of the buffer to allocate. Used when bAllocateNew is true. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) \ - ((OMX_COMPONENTTYPE*)hComponent)->AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) /* Macro End */ - - -/** The OMX_FreeBuffer macro will release a buffer header from the component - which was allocated using either OMX_AllocateBuffer or OMX_UseBuffer. If - the component allocated the buffer (see the OMX_UseBuffer macro) then - the component shall free the buffer and buffer header. This is a - blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) /* Macro End */ - - -/** The OMX_EmptyThisBuffer macro will send a buffer full of data to an - input port of a component. The buffer will be emptied by the component - and returned to the application via the EmptyBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then empty the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_StateExecuting. If nPortIndex does not specify an input - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_EmptyThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->EmptyThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - -/** The OMX_FillThisBuffer macro will send an empty buffer to an - output port of a component. The buffer will be filled by the component - and returned to the application via the FillBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then fill the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_ExecutingState. If nPortIndex does not specify an output - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FillThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FillThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - - -/** The OMX_UseEGLImage macro will request that the component use - a EGLImage provided by EGL (and allocate its own buffer header) - This is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header. Note that the memory location used - for this buffer is NOT visible to the IL Client. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] eglImage - eglImage contains the handle of the EGLImage to use as a buffer on the - specified port. The component is expected to validate properties of - the EGLImage against the configuration of the port to ensure the component - can use the EGLImage as a buffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) - -/** The OMX_Init method is used to initialize the OMX core. It shall be the - first call made into OMX and it should only be executed one time without - an interviening OMX_Deinit call. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Init(void); - - -/** The OMX_Deinit method is used to deinitialize the OMX core. It shall be - the last call made into OMX. In the event that the core determines that - thare are components loaded when this call is made, the core may return - with an error rather than try to unload the components. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Deinit(void); - - -/** The OMX_ComponentNameEnum method will enumerate through all the names of - recognised valid components in the system. This function is provided - as a means to detect all the components in the system run-time. There is - no strict ordering to the enumeration order of component names, although - each name will only be enumerated once. If the OMX core supports run-time - installation of new components, it is only requried to detect newly - installed components when the first call to enumerate component names - is made (i.e. when nIndex is 0x0). - - The core should return from this call in 20 msec. - - @param [out] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] nNameLength - number of characters in the cComponentName string. With all - component name strings restricted to less than 128 characters - (including the trailing null) it is recomended that the caller - provide a input string for the cComponentName of 128 characters. - @param [in] nIndex - number containing the enumeration index for the component. - Multiple calls to OMX_ComponentNameEnum with increasing values - of nIndex will enumerate through the component names in the - system until OMX_ErrorNoMore is returned. The value of nIndex - is 0 to (N-1), where N is the number of valid installed components - in the system. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. When the value of nIndex exceeds the number of - components in the system minus 1, OMX_ErrorNoMore will be - returned. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_ComponentNameEnum( - OMX_OUT OMX_STRING cComponentName, - OMX_IN OMX_U32 nNameLength, - OMX_IN OMX_U32 nIndex); - - -/** The OMX_GetHandle method will locate the component specified by the - component name given, load that component into memory and then invoke - the component's methods to create an instance of the component. - - The core should return from this call within 20 msec. - - @param [out] pHandle - pointer to an OMX_HANDLETYPE pointer to be filled in by this method. - @param [in] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] pAppData - pointer to an application defined value that will be returned - during callbacks so that the application can identify the source - of the callback. - @param [in] pCallBacks - pointer to a OMX_CALLBACKTYPE structure that will be passed to the - component to initialize it with. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_GetHandle( - OMX_OUT OMX_HANDLETYPE* pHandle, - OMX_IN OMX_STRING cComponentName, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_CALLBACKTYPE* pCallBacks); - - -/** The OMX_FreeHandle method will free a handle allocated by the OMX_GetHandle - method. If the component reference count goes to zero, the component will - be unloaded from memory. - - The core should return from this call within 20 msec when the component is - in the OMX_StateLoaded state. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_FreeHandle( - OMX_IN OMX_HANDLETYPE hComponent); - - - -/** The OMX_SetupTunnel method will handle the necessary calls to the components - to setup the specified tunnel the two components. NOTE: This is - an actual method (not a #define macro). This method will make calls into - the component ComponentTunnelRequest method to do the actual tunnel - connection. - - The ComponentTunnelRequest method on both components will be called. - This method shall not be called unless the component is in the - OMX_StateLoaded state except when the ports used for the tunnel are - disabled. In this case, the component may be in the OMX_StateExecuting, - OMX_StatePause, or OMX_StateIdle states. - - The core should return from this call within 20 msec. - - @param [in] hOutput - Handle of the component to be accessed. Also this is the handle - of the component whose port, specified in the nPortOutput parameter - will be used the source for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hOutput be the source for the data when - tunelling (i.e. nPortOutput is an output port). If 0x0, the component - specified in hInput will have it's port specified in nPortInput - setup for communication with the application / IL client. - @param [in] nPortOutput - nPortOutput is used to select the source port on component to be - used in the tunnel. - @param [in] hInput - This is the component to setup the tunnel with. This is the handle - of the component whose port, specified in the nPortInput parameter - will be used the destination for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hInput be the destination for the data when - tunelling (i.e. nPortInut is an input port). If 0x0, the component - specified in hOutput will have it's port specified in nPortPOutput - setup for communication with the application / IL client. - @param [in] nPortInput - nPortInput is used to select the destination port on component to be - used in the tunnel. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - When OMX_ErrorNotImplemented is returned, one or both components is - a non-interop component and does not support tunneling. - - On failure, the ports of both components are setup for communication - with the application / IL Client. - @ingroup core tun - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_SetupTunnel( - OMX_IN OMX_HANDLETYPE hOutput, - OMX_IN OMX_U32 nPortOutput, - OMX_IN OMX_HANDLETYPE hInput, - OMX_IN OMX_U32 nPortInput); - -/** @ingroup cp */ -OMX_API OMX_ERRORTYPE OMX_GetContentPipe( - OMX_OUT OMX_HANDLETYPE *hPipe, - OMX_IN OMX_STRING szURI); - -/** The OMX_GetComponentsOfRole method will return the number of components that support the given - role and (if the compNames field is non-NULL) the names of those components. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the compNames field NULL to determine the number of component names - * second call this function with the compNames field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] role - This is generic standard component name consisting only of component class - name and the type within that class (e.g. 'audio_decoder.aac'). - @param [inout] pNumComps - This is used both as input and output. - - If compNames is NULL, the input is ignored and the output specifies how many components support - the given role. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of components string names listed within the compNames parameter. - @param [inout] compNames - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings which accepts - a list of the names of all physical components that implement the specified standard component name. - Each name is NULL terminated. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetComponentsOfRole ( - OMX_IN OMX_STRING role, - OMX_INOUT OMX_U32 *pNumComps, - OMX_INOUT OMX_U8 **compNames); - -/** The OMX_GetRolesOfComponent method will return the number of roles supported by the given - component and (if the roles field is non-NULL) the names of those roles. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the roles field NULL to determine the number of role names - * second call this function with the roles field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] compName - This is the name of the component being queried about. - @param [inout] pNumRoles - This is used both as input and output. - - If roles is NULL, the input is ignored and the output specifies how many roles the component supports. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of roles string names listed within the roles parameter. - @param [out] roles - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings - which accepts a list of the names of all standard components roles implemented on the - specified component name. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetRolesOfComponent ( - OMX_IN OMX_STRING compName, - OMX_INOUT OMX_U32 *pNumRoles, - OMX_OUT OMX_U8 **roles); - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_CoreExt.h b/third_party/openmax/include/OMX_CoreExt.h deleted file mode 100644 index 3ec14b05f3..0000000000 --- a/third_party/openmax/include/OMX_CoreExt.h +++ /dev/null @@ -1,66 +0,0 @@ -/* - * Copyright (c) 2009 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_CoreExt.h - OpenMax IL version 1.1.2 - * The OMX_CoreExt header file contains extensions to the definitions used - * by both the application and the component to access common items. - */ - -#ifndef OMX_CoreExt_h -#define OMX_CoreExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** Event type extensions. */ -typedef enum OMX_EVENTEXTTYPE -{ - OMX_EventIndexSettingChanged = OMX_EventKhronosExtensions, /**< component signals the IL client of a change - in a param, config, or extension */ - OMX_EventExtMax = 0x7FFFFFFF -} OMX_EVENTEXTTYPE; - - -/** Enable or disable a callback event. */ -typedef struct OMX_CONFIG_CALLBACKREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_INDEXTYPE nIndex; /**< the index the callback is requested for */ - OMX_BOOL bEnable; /**< enable (OMX_TRUE) or disable (OMX_FALSE) the callback */ -} OMX_CONFIG_CALLBACKREQUESTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_CoreExt_h */ -/* File EOF */ diff --git a/third_party/openmax/include/OMX_IVCommon.h b/third_party/openmax/include/OMX_IVCommon.h deleted file mode 100644 index ec717565a0..0000000000 --- a/third_party/openmax/include/OMX_IVCommon.h +++ /dev/null @@ -1,933 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_IVCommon.h - OpenMax IL version 1.1.2 - * The structures needed by Video and Image components to exchange - * parameters and configuration data with the components. - */ -#ifndef OMX_IVCommon_h -#define OMX_IVCommon_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** - * Each OMX header must include all required header files to allow the header - * to compile without errors. The includes below are required for this header - * file to compile successfully - */ - -#include - -/** @defgroup iv OpenMAX IL Imaging and Video Domain - * Common structures for OpenMAX IL Imaging and Video domains - * @{ - */ - - -/** - * Enumeration defining possible uncompressed image/video formats. - * - * ENUMS: - * Unused : Placeholder value when format is N/A - * Monochrome : black and white - * 8bitRGB332 : Red 7:5, Green 4:2, Blue 1:0 - * 12bitRGB444 : Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB4444 : Alpha 15:12, Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB1555 : Alpha 15, Red 14:10, Green 9:5, Blue 4:0 - * 16bitRGB565 : Red 15:11, Green 10:5, Blue 4:0 - * 16bitBGR565 : Blue 15:11, Green 10:5, Red 4:0 - * 18bitRGB666 : Red 17:12, Green 11:6, Blue 5:0 - * 18bitARGB1665 : Alpha 17, Red 16:11, Green 10:5, Blue 4:0 - * 19bitARGB1666 : Alpha 18, Red 17:12, Green 11:6, Blue 5:0 - * 24bitRGB888 : Red 24:16, Green 15:8, Blue 7:0 - * 24bitBGR888 : Blue 24:16, Green 15:8, Red 7:0 - * 24bitARGB1887 : Alpha 23, Red 22:15, Green 14:7, Blue 6:0 - * 25bitARGB1888 : Alpha 24, Red 23:16, Green 15:8, Blue 7:0 - * 32bitBGRA8888 : Blue 31:24, Green 23:16, Red 15:8, Alpha 7:0 - * 32bitARGB8888 : Alpha 31:24, Red 23:16, Green 15:8, Blue 7:0 - * YUV411Planar : U,Y are subsampled by a factor of 4 horizontally - * YUV411PackedPlanar : packed per payload in planar slices - * YUV420Planar : Three arrays Y,U,V. - * YUV420PackedPlanar : packed per payload in planar slices - * YUV420SemiPlanar : Two arrays, one is all Y, the other is U and V - * YUV422Planar : Three arrays Y,U,V. - * YUV422PackedPlanar : packed per payload in planar slices - * YUV422SemiPlanar : Two arrays, one is all Y, the other is U and V - * YCbYCr : Organized as 16bit YUYV (i.e. YCbYCr) - * YCrYCb : Organized as 16bit YVYU (i.e. YCrYCb) - * CbYCrY : Organized as 16bit UYVY (i.e. CbYCrY) - * CrYCbY : Organized as 16bit VYUY (i.e. CrYCbY) - * YUV444Interleaved : Each pixel contains equal parts YUV - * RawBayer8bit : SMIA camera output format - * RawBayer10bit : SMIA camera output format - * RawBayer8bitcompressed : SMIA camera output format - */ -typedef enum OMX_COLOR_FORMATTYPE { - OMX_COLOR_FormatUnused, - OMX_COLOR_FormatMonochrome, - OMX_COLOR_Format8bitRGB332, - OMX_COLOR_Format12bitRGB444, - OMX_COLOR_Format16bitARGB4444, - OMX_COLOR_Format16bitARGB1555, - OMX_COLOR_Format16bitRGB565, - OMX_COLOR_Format16bitBGR565, - OMX_COLOR_Format18bitRGB666, - OMX_COLOR_Format18bitARGB1665, - OMX_COLOR_Format19bitARGB1666, - OMX_COLOR_Format24bitRGB888, - OMX_COLOR_Format24bitBGR888, - OMX_COLOR_Format24bitARGB1887, - OMX_COLOR_Format25bitARGB1888, - OMX_COLOR_Format32bitBGRA8888, - OMX_COLOR_Format32bitARGB8888, - OMX_COLOR_FormatYUV411Planar, - OMX_COLOR_FormatYUV411PackedPlanar, - OMX_COLOR_FormatYUV420Planar, - OMX_COLOR_FormatYUV420PackedPlanar, - OMX_COLOR_FormatYUV420SemiPlanar, - OMX_COLOR_FormatYUV422Planar, - OMX_COLOR_FormatYUV422PackedPlanar, - OMX_COLOR_FormatYUV422SemiPlanar, - OMX_COLOR_FormatYCbYCr, - OMX_COLOR_FormatYCrYCb, - OMX_COLOR_FormatCbYCrY, - OMX_COLOR_FormatCrYCbY, - OMX_COLOR_FormatYUV444Interleaved, - OMX_COLOR_FormatRawBayer8bit, - OMX_COLOR_FormatRawBayer10bit, - OMX_COLOR_FormatRawBayer8bitcompressed, - OMX_COLOR_FormatL2, - OMX_COLOR_FormatL4, - OMX_COLOR_FormatL8, - OMX_COLOR_FormatL16, - OMX_COLOR_FormatL24, - OMX_COLOR_FormatL32, - OMX_COLOR_FormatYUV420PackedSemiPlanar, - OMX_COLOR_FormatYUV422PackedSemiPlanar, - OMX_COLOR_Format18BitBGR666, - OMX_COLOR_Format24BitARGB6666, - OMX_COLOR_Format24BitABGR6666, - OMX_COLOR_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_COLOR_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - /** - -/** @defgroup imaging OpenMAX IL Imaging Domain - * @ingroup iv - * Structures for OpenMAX IL Imaging domain - * @{ - */ - -/** - * Enumeration used to define the possible image compression coding. - */ -typedef enum OMX_IMAGE_CODINGTYPE { - OMX_IMAGE_CodingUnused, /**< Value when format is N/A */ - OMX_IMAGE_CodingAutoDetect, /**< Auto detection of image format */ - OMX_IMAGE_CodingJPEG, /**< JPEG/JFIF image format */ - OMX_IMAGE_CodingJPEG2K, /**< JPEG 2000 image format */ - OMX_IMAGE_CodingEXIF, /**< EXIF image format */ - OMX_IMAGE_CodingTIFF, /**< TIFF image format */ - OMX_IMAGE_CodingGIF, /**< Graphics image format */ - OMX_IMAGE_CodingPNG, /**< PNG image format */ - OMX_IMAGE_CodingLZW, /**< LZW image format */ - OMX_IMAGE_CodingBMP, /**< Windows Bitmap format */ - OMX_IMAGE_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_CodingMax = 0x7FFFFFFF -} OMX_IMAGE_CODINGTYPE; - - -/** - * Data structure used to define an image path. The number of image paths - * for input and output will vary by type of the image component. - * - * Input (aka Source) : Zero Inputs, one Output, - * Splitter : One Input, 2 or more Outputs, - * Processing Element : One Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : One Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output - * image path. If additional vendor specific data is required, it should - * be transmitted to the component using the CustomCommand function. - * Compliant components will prepopulate this structure with optimal - * values during the OMX_GetParameter() command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nFrameHeight : Height of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nStride : Number of bytes per span of an image (i.e. - * indicates the number of bytes to get from - * span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of - * the component. When OMX_IMAGE_CodingUnused is - * specified, eColorFormat is valid - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_IMAGE_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_BOOL bFlagErrorConcealment; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_IMAGE_PORTDEFINITIONTYPE; - - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_IMAGE_CodingUnused is specified, - * eColorFormat is valid - * eColorFormat : Decompressed format used by this component - */ -typedef struct OMX_IMAGE_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; -} OMX_IMAGE_PARAM_PORTFORMATTYPE; - - -/** - * Flash control type - * - * ENUMS - * Torch : Flash forced constantly on - */ -typedef enum OMX_IMAGE_FLASHCONTROLTYPE { - OMX_IMAGE_FlashControlOn = 0, - OMX_IMAGE_FlashControlOff, - OMX_IMAGE_FlashControlAuto, - OMX_IMAGE_FlashControlRedEyeReduction, - OMX_IMAGE_FlashControlFillin, - OMX_IMAGE_FlashControlTorch, - OMX_IMAGE_FlashControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FlashControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FlashControlMax = 0x7FFFFFFF -} OMX_IMAGE_FLASHCONTROLTYPE; - - -/** - * Flash control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFlashControl : Flash control type - */ -typedef struct OMX_IMAGE_PARAM_FLASHCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FLASHCONTROLTYPE eFlashControl; -} OMX_IMAGE_PARAM_FLASHCONTROLTYPE; - - -/** - * Focus control type - */ -typedef enum OMX_IMAGE_FOCUSCONTROLTYPE { - OMX_IMAGE_FocusControlOn = 0, - OMX_IMAGE_FocusControlOff, - OMX_IMAGE_FocusControlAuto, - OMX_IMAGE_FocusControlAutoLock, - OMX_IMAGE_FocusControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FocusControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FocusControlMax = 0x7FFFFFFF -} OMX_IMAGE_FOCUSCONTROLTYPE; - - -/** - * Focus control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFocusControl : Focus control - * nFocusSteps : Focus can take on values from 0 mm to infinity. - * Interest is only in number of steps over this range. - * nFocusStepIndex : Current focus step index - */ -typedef struct OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FOCUSCONTROLTYPE eFocusControl; - OMX_U32 nFocusSteps; - OMX_U32 nFocusStepIndex; -} OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE; - - -/** - * Q Factor for JPEG compression, which controls the tradeoff between image - * quality and size. Q Factor provides a more simple means of controlling - * JPEG compression quality, without directly programming Quantization - * tables for chroma and luma - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nQFactor : JPEG Q factor value in the range of 1-100. A factor of 1 - * produces the smallest, worst quality images, and a factor - * of 100 produces the largest, best quality images. A - * typical default is 75 for small good quality images - */ -typedef struct OMX_IMAGE_PARAM_QFACTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQFactor; -} OMX_IMAGE_PARAM_QFACTORTYPE; - -/** - * Quantization table type - */ - -typedef enum OMX_IMAGE_QUANTIZATIONTABLETYPE { - OMX_IMAGE_QuantizationTableLuma = 0, - OMX_IMAGE_QuantizationTableChroma, - OMX_IMAGE_QuantizationTableChromaCb, - OMX_IMAGE_QuantizationTableChromaCr, - OMX_IMAGE_QuantizationTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_QuantizationTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_QuantizationTableMax = 0x7FFFFFFF -} OMX_IMAGE_QUANTIZATIONTABLETYPE; - -/** - * JPEG quantization tables are used to determine DCT compression for - * YUV data, as an alternative to specifying Q factor, providing exact - * control of compression - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eQuantizationTable : Quantization table type - * nQuantizationMatrix[64] : JPEG quantization table of coefficients stored - * in increasing columns then by rows of data (i.e. - * row 1, ... row 8). Quantization values are in - * the range 0-255 and stored in linear order - * (i.e. the component will zig-zag the - * quantization table data if required internally) - */ -typedef struct OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_QUANTIZATIONTABLETYPE eQuantizationTable; - OMX_U8 nQuantizationMatrix[64]; -} OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE; - - -/** - * Huffman table type, the same Huffman table is applied for chroma and - * luma component - */ -typedef enum OMX_IMAGE_HUFFMANTABLETYPE { - OMX_IMAGE_HuffmanTableAC = 0, - OMX_IMAGE_HuffmanTableDC, - OMX_IMAGE_HuffmanTableACLuma, - OMX_IMAGE_HuffmanTableACChroma, - OMX_IMAGE_HuffmanTableDCLuma, - OMX_IMAGE_HuffmanTableDCChroma, - OMX_IMAGE_HuffmanTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_HuffmanTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_HuffmanTableMax = 0x7FFFFFFF -} OMX_IMAGE_HUFFMANTABLETYPE; - -/** - * JPEG Huffman table - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eHuffmanTable : Huffman table type - * nNumberOfHuffmanCodeOfLength[16] : 0-16, number of Huffman codes of each - * possible length - * nHuffmanTable[256] : 0-255, the size used for AC and DC - * HuffmanTable are 16 and 162 - */ -typedef struct OMX_IMAGE_PARAM_HUFFMANTTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_HUFFMANTABLETYPE eHuffmanTable; - OMX_U8 nNumberOfHuffmanCodeOfLength[16]; - OMX_U8 nHuffmanTable[256]; -}OMX_IMAGE_PARAM_HUFFMANTTABLETYPE; - -/** @} */ -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Index.h b/third_party/openmax/include/OMX_Index.h deleted file mode 100644 index a1f17487d3..0000000000 --- a/third_party/openmax/include/OMX_Index.h +++ /dev/null @@ -1,259 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Index.h - OpenMax IL version 1.1.2 - * The OMX_Index header file contains the definitions for both applications - * and components . - */ - - -#ifndef OMX_Index_h -#define OMX_Index_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** The OMX_INDEXTYPE enumeration is used to select a structure when either - * getting or setting parameters and/or configuration data. Each entry in - * this enumeration maps to an OMX specified structure. When the - * OMX_GetParameter, OMX_SetParameter, OMX_GetConfig or OMX_SetConfig methods - * are used, the second parameter will always be an entry from this enumeration - * and the third entry will be the structure shown in the comments for the entry. - * For example, if the application is initializing a cropping function, the - * OMX_SetConfig command would have OMX_IndexConfigCommonInputCrop as the second parameter - * and would send a pointer to an initialized OMX_RECTTYPE structure as the - * third parameter. - * - * The enumeration entries named with the OMX_Config prefix are sent using - * the OMX_SetConfig command and the enumeration entries named with the - * OMX_PARAM_ prefix are sent using the OMX_SetParameter command. - */ -typedef enum OMX_INDEXTYPE { - - OMX_IndexComponentStartUnused = 0x01000000, - OMX_IndexParamPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamAudioInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamImageInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamVideoInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamOtherInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamNumAvailableStreams, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamActiveStream, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamSuspensionPolicy, /**< reference: OMX_PARAM_SUSPENSIONPOLICYTYPE */ - OMX_IndexParamComponentSuspended, /**< reference: OMX_PARAM_SUSPENSIONTYPE */ - OMX_IndexConfigCapturing, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigCaptureMode, /**< reference: OMX_CONFIG_CAPTUREMODETYPE */ - OMX_IndexAutoPauseAfterCapture, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexParamContentURI, /**< reference: OMX_PARAM_CONTENTURITYPE */ - OMX_IndexParamCustomContentPipe, /**< reference: OMX_PARAM_CONTENTPIPETYPE */ - OMX_IndexParamDisableResourceConcealment, /**< reference: OMX_RESOURCECONCEALMENTTYPE */ - OMX_IndexConfigMetadataItemCount, /**< reference: OMX_CONFIG_METADATAITEMCOUNTTYPE */ - OMX_IndexConfigContainerNodeCount, /**< reference: OMX_CONFIG_CONTAINERNODECOUNTTYPE */ - OMX_IndexConfigMetadataItem, /**< reference: OMX_CONFIG_METADATAITEMTYPE */ - OMX_IndexConfigCounterNodeID, /**< reference: OMX_CONFIG_CONTAINERNODEIDTYPE */ - OMX_IndexParamMetadataFilterType, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexParamMetadataKeyFilter, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexConfigPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamStandardComponentRole, /**< reference: OMX_PARAM_COMPONENTROLETYPE */ - - OMX_IndexPortStartUnused = 0x02000000, - OMX_IndexParamPortDefinition, /**< reference: OMX_PARAM_PORTDEFINITIONTYPE */ - OMX_IndexParamCompBufferSupplier, /**< reference: OMX_PARAM_BUFFERSUPPLIERTYPE */ - OMX_IndexReservedStartUnused = 0x03000000, - - /* Audio parameters and configurations */ - OMX_IndexAudioStartUnused = 0x04000000, - OMX_IndexParamAudioPortFormat, /**< reference: OMX_AUDIO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamAudioPcm, /**< reference: OMX_AUDIO_PARAM_PCMMODETYPE */ - OMX_IndexParamAudioAac, /**< reference: OMX_AUDIO_PARAM_AACPROFILETYPE */ - OMX_IndexParamAudioRa, /**< reference: OMX_AUDIO_PARAM_RATYPE */ - OMX_IndexParamAudioMp3, /**< reference: OMX_AUDIO_PARAM_MP3TYPE */ - OMX_IndexParamAudioAdpcm, /**< reference: OMX_AUDIO_PARAM_ADPCMTYPE */ - OMX_IndexParamAudioG723, /**< reference: OMX_AUDIO_PARAM_G723TYPE */ - OMX_IndexParamAudioG729, /**< reference: OMX_AUDIO_PARAM_G729TYPE */ - OMX_IndexParamAudioAmr, /**< reference: OMX_AUDIO_PARAM_AMRTYPE */ - OMX_IndexParamAudioWma, /**< reference: OMX_AUDIO_PARAM_WMATYPE */ - OMX_IndexParamAudioSbc, /**< reference: OMX_AUDIO_PARAM_SBCTYPE */ - OMX_IndexParamAudioMidi, /**< reference: OMX_AUDIO_PARAM_MIDITYPE */ - OMX_IndexParamAudioGsm_FR, /**< reference: OMX_AUDIO_PARAM_GSMFRTYPE */ - OMX_IndexParamAudioMidiLoadUserSound, /**< reference: OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE */ - OMX_IndexParamAudioG726, /**< reference: OMX_AUDIO_PARAM_G726TYPE */ - OMX_IndexParamAudioGsm_EFR, /**< reference: OMX_AUDIO_PARAM_GSMEFRTYPE */ - OMX_IndexParamAudioGsm_HR, /**< reference: OMX_AUDIO_PARAM_GSMHRTYPE */ - OMX_IndexParamAudioPdc_FR, /**< reference: OMX_AUDIO_PARAM_PDCFRTYPE */ - OMX_IndexParamAudioPdc_EFR, /**< reference: OMX_AUDIO_PARAM_PDCEFRTYPE */ - OMX_IndexParamAudioPdc_HR, /**< reference: OMX_AUDIO_PARAM_PDCHRTYPE */ - OMX_IndexParamAudioTdma_FR, /**< reference: OMX_AUDIO_PARAM_TDMAFRTYPE */ - OMX_IndexParamAudioTdma_EFR, /**< reference: OMX_AUDIO_PARAM_TDMAEFRTYPE */ - OMX_IndexParamAudioQcelp8, /**< reference: OMX_AUDIO_PARAM_QCELP8TYPE */ - OMX_IndexParamAudioQcelp13, /**< reference: OMX_AUDIO_PARAM_QCELP13TYPE */ - OMX_IndexParamAudioEvrc, /**< reference: OMX_AUDIO_PARAM_EVRCTYPE */ - OMX_IndexParamAudioSmv, /**< reference: OMX_AUDIO_PARAM_SMVTYPE */ - OMX_IndexParamAudioVorbis, /**< reference: OMX_AUDIO_PARAM_VORBISTYPE */ - - OMX_IndexConfigAudioMidiImmediateEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE */ - OMX_IndexConfigAudioMidiControl, /**< reference: OMX_AUDIO_CONFIG_MIDICONTROLTYPE */ - OMX_IndexConfigAudioMidiSoundBankProgram, /**< reference: OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE */ - OMX_IndexConfigAudioMidiStatus, /**< reference: OMX_AUDIO_CONFIG_MIDISTATUSTYPE */ - OMX_IndexConfigAudioMidiMetaEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE */ - OMX_IndexConfigAudioMidiMetaEventData, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE */ - OMX_IndexConfigAudioVolume, /**< reference: OMX_AUDIO_CONFIG_VOLUMETYPE */ - OMX_IndexConfigAudioBalance, /**< reference: OMX_AUDIO_CONFIG_BALANCETYPE */ - OMX_IndexConfigAudioChannelMute, /**< reference: OMX_AUDIO_CONFIG_CHANNELMUTETYPE */ - OMX_IndexConfigAudioMute, /**< reference: OMX_AUDIO_CONFIG_MUTETYPE */ - OMX_IndexConfigAudioLoudness, /**< reference: OMX_AUDIO_CONFIG_LOUDNESSTYPE */ - OMX_IndexConfigAudioEchoCancelation, /**< reference: OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE */ - OMX_IndexConfigAudioNoiseReduction, /**< reference: OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE */ - OMX_IndexConfigAudioBass, /**< reference: OMX_AUDIO_CONFIG_BASSTYPE */ - OMX_IndexConfigAudioTreble, /**< reference: OMX_AUDIO_CONFIG_TREBLETYPE */ - OMX_IndexConfigAudioStereoWidening, /**< reference: OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE */ - OMX_IndexConfigAudioChorus, /**< reference: OMX_AUDIO_CONFIG_CHORUSTYPE */ - OMX_IndexConfigAudioEqualizer, /**< reference: OMX_AUDIO_CONFIG_EQUALIZERTYPE */ - OMX_IndexConfigAudioReverberation, /**< reference: OMX_AUDIO_CONFIG_REVERBERATIONTYPE */ - OMX_IndexConfigAudioChannelVolume, /**< reference: OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE */ - - /* Image specific parameters and configurations */ - OMX_IndexImageStartUnused = 0x05000000, - OMX_IndexParamImagePortFormat, /**< reference: OMX_IMAGE_PARAM_PORTFORMATTYPE */ - OMX_IndexParamFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - OMX_IndexConfigFocusControl, /**< reference: OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE */ - OMX_IndexParamQFactor, /**< reference: OMX_IMAGE_PARAM_QFACTORTYPE */ - OMX_IndexParamQuantizationTable, /**< reference: OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE */ - OMX_IndexParamHuffmanTable, /**< reference: OMX_IMAGE_PARAM_HUFFMANTTABLETYPE */ - OMX_IndexConfigFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - - /* Video specific parameters and configurations */ - OMX_IndexVideoStartUnused = 0x06000000, - OMX_IndexParamVideoPortFormat, /**< reference: OMX_VIDEO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamVideoQuantization, /**< reference: OMX_VIDEO_PARAM_QUANTIZATIONTYPE */ - OMX_IndexParamVideoFastUpdate, /**< reference: OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE */ - OMX_IndexParamVideoBitrate, /**< reference: OMX_VIDEO_PARAM_BITRATETYPE */ - OMX_IndexParamVideoMotionVector, /**< reference: OMX_VIDEO_PARAM_MOTIONVECTORTYPE */ - OMX_IndexParamVideoIntraRefresh, /**< reference: OMX_VIDEO_PARAM_INTRAREFRESHTYPE */ - OMX_IndexParamVideoErrorCorrection, /**< reference: OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE */ - OMX_IndexParamVideoVBSMC, /**< reference: OMX_VIDEO_PARAM_VBSMCTYPE */ - OMX_IndexParamVideoMpeg2, /**< reference: OMX_VIDEO_PARAM_MPEG2TYPE */ - OMX_IndexParamVideoMpeg4, /**< reference: OMX_VIDEO_PARAM_MPEG4TYPE */ - OMX_IndexParamVideoWmv, /**< reference: OMX_VIDEO_PARAM_WMVTYPE */ - OMX_IndexParamVideoRv, /**< reference: OMX_VIDEO_PARAM_RVTYPE */ - OMX_IndexParamVideoAvc, /**< reference: OMX_VIDEO_PARAM_AVCTYPE */ - OMX_IndexParamVideoH263, /**< reference: OMX_VIDEO_PARAM_H263TYPE */ - OMX_IndexParamVideoProfileLevelQuerySupported, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexParamVideoProfileLevelCurrent, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexConfigVideoBitrate, /**< reference: OMX_VIDEO_CONFIG_BITRATETYPE */ - OMX_IndexConfigVideoFramerate, /**< reference: OMX_CONFIG_FRAMERATETYPE */ - OMX_IndexConfigVideoIntraVOPRefresh, /**< reference: OMX_CONFIG_INTRAREFRESHVOPTYPE */ - OMX_IndexConfigVideoIntraMBRefresh, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexConfigVideoMBErrorReporting, /**< reference: OMX_CONFIG_MBERRORREPORTINGTYPE */ - OMX_IndexParamVideoMacroblocksPerFrame, /**< reference: OMX_PARAM_MACROBLOCKSTYPE */ - OMX_IndexConfigVideoMacroBlockErrorMap, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexParamVideoSliceFMO, /**< reference: OMX_VIDEO_PARAM_AVCSLICEFMO */ - OMX_IndexConfigVideoAVCIntraPeriod, /**< reference: OMX_VIDEO_CONFIG_AVCINTRAPERIOD */ - OMX_IndexConfigVideoNalSize, /**< reference: OMX_VIDEO_CONFIG_NALSIZE */ - OMX_IndexConfigCommonDeinterlace, /**< reference: OMX_VIDEO_CONFIG_DEINTERLACE */ - - /* Image & Video common Configurations */ - OMX_IndexCommonStartUnused = 0x07000000, - OMX_IndexParamCommonDeblocking, /**< reference: OMX_PARAM_DEBLOCKINGTYPE */ - OMX_IndexParamCommonSensorMode, /**< reference: OMX_PARAM_SENSORMODETYPE */ - OMX_IndexParamCommonInterleave, /**< reference: OMX_PARAM_INTERLEAVETYPE */ - OMX_IndexConfigCommonColorFormatConversion, /**< reference: OMX_CONFIG_COLORCONVERSIONTYPE */ - OMX_IndexConfigCommonScale, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonImageFilter, /**< reference: OMX_CONFIG_IMAGEFILTERTYPE */ - OMX_IndexConfigCommonColorEnhancement, /**< reference: OMX_CONFIG_COLORENHANCEMENTTYPE */ - OMX_IndexConfigCommonColorKey, /**< reference: OMX_CONFIG_COLORKEYTYPE */ - OMX_IndexConfigCommonColorBlend, /**< reference: OMX_CONFIG_COLORBLENDTYPE */ - OMX_IndexConfigCommonFrameStabilisation,/**< reference: OMX_CONFIG_FRAMESTABTYPE */ - OMX_IndexConfigCommonRotate, /**< reference: OMX_CONFIG_ROTATIONTYPE */ - OMX_IndexConfigCommonMirror, /**< reference: OMX_CONFIG_MIRRORTYPE */ - OMX_IndexConfigCommonOutputPosition, /**< reference: OMX_CONFIG_POINTTYPE */ - OMX_IndexConfigCommonInputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonOutputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDigitalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonOpticalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE*/ - OMX_IndexConfigCommonWhiteBalance, /**< reference: OMX_CONFIG_WHITEBALCONTROLTYPE */ - OMX_IndexConfigCommonExposure, /**< reference: OMX_CONFIG_EXPOSURECONTROLTYPE */ - OMX_IndexConfigCommonContrast, /**< reference: OMX_CONFIG_CONTRASTTYPE */ - OMX_IndexConfigCommonBrightness, /**< reference: OMX_CONFIG_BRIGHTNESSTYPE */ - OMX_IndexConfigCommonBacklight, /**< reference: OMX_CONFIG_BACKLIGHTTYPE */ - OMX_IndexConfigCommonGamma, /**< reference: OMX_CONFIG_GAMMATYPE */ - OMX_IndexConfigCommonSaturation, /**< reference: OMX_CONFIG_SATURATIONTYPE */ - OMX_IndexConfigCommonLightness, /**< reference: OMX_CONFIG_LIGHTNESSTYPE */ - OMX_IndexConfigCommonExclusionRect, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDithering, /**< reference: OMX_CONFIG_DITHERTYPE */ - OMX_IndexConfigCommonPlaneBlend, /**< reference: OMX_CONFIG_PLANEBLENDTYPE */ - OMX_IndexConfigCommonExposureValue, /**< reference: OMX_CONFIG_EXPOSUREVALUETYPE */ - OMX_IndexConfigCommonOutputSize, /**< reference: OMX_FRAMESIZETYPE */ - OMX_IndexParamCommonExtraQuantData, /**< reference: OMX_OTHER_EXTRADATATYPE */ - OMX_IndexConfigCommonFocusRegion, /**< reference: OMX_CONFIG_FOCUSREGIONTYPE */ - OMX_IndexConfigCommonFocusStatus, /**< reference: OMX_PARAM_FOCUSSTATUSTYPE */ - OMX_IndexConfigCommonTransitionEffect, /**< reference: OMX_CONFIG_TRANSITIONEFFECTTYPE */ - - /* Reserved Configuration range */ - OMX_IndexOtherStartUnused = 0x08000000, - OMX_IndexParamOtherPortFormat, /**< reference: OMX_OTHER_PARAM_PORTFORMATTYPE */ - OMX_IndexConfigOtherPower, /**< reference: OMX_OTHER_CONFIG_POWERTYPE */ - OMX_IndexConfigOtherStats, /**< reference: OMX_OTHER_CONFIG_STATSTYPE */ - - - /* Reserved Time range */ - OMX_IndexTimeStartUnused = 0x09000000, - OMX_IndexConfigTimeScale, /**< reference: OMX_TIME_CONFIG_SCALETYPE */ - OMX_IndexConfigTimeClockState, /**< reference: OMX_TIME_CONFIG_CLOCKSTATETYPE */ - OMX_IndexConfigTimeActiveRefClock, /**< reference: OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE */ - OMX_IndexConfigTimeCurrentMediaTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentWallTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentAudioReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeCurrentVideoReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeMediaTimeRequest, /**< reference: OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE (write only) */ - OMX_IndexConfigTimeClientStartTime, /** - - -/** Khronos standard extension indices. - -This enum lists the current Khronos extension indices to OpenMAX IL. -*/ -typedef enum OMX_INDEXEXTTYPE { - - /* Component parameters and configurations */ - OMX_IndexExtComponentStartUnused = OMX_IndexKhronosExtensions + 0x00100000, - OMX_IndexConfigCallbackRequest, /**< reference: OMX_CONFIG_CALLBACKREQUESTTYPE */ - OMX_IndexConfigCommitMode, /**< reference: OMX_CONFIG_COMMITMODETYPE */ - OMX_IndexConfigCommit, /**< reference: OMX_CONFIG_COMMITTYPE */ - - /* Port parameters and configurations */ - OMX_IndexExtPortStartUnused = OMX_IndexKhronosExtensions + 0x00200000, - - /* Audio parameters and configurations */ - OMX_IndexExtAudioStartUnused = OMX_IndexKhronosExtensions + 0x00400000, - - /* Image parameters and configurations */ - OMX_IndexExtImageStartUnused = OMX_IndexKhronosExtensions + 0x00500000, - - /* Video parameters and configurations */ - OMX_IndexExtVideoStartUnused = OMX_IndexKhronosExtensions + 0x00600000, - OMX_IndexParamNalStreamFormatSupported, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormat, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormatSelect, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamVideoVp8, /**< reference: OMX_VIDEO_PARAM_VP8TYPE */ - OMX_IndexConfigVideoVp8ReferenceFrame, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMETYPE */ - OMX_IndexConfigVideoVp8ReferenceFrameType, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE */ - OMX_IndexParamVideoReserved, /**< Reserved for future index */ - OMX_IndexParamVideoHevc, /**< reference: OMX_VIDEO_PARAM_HEVCTYPE */ - - /* Image & Video common configurations */ - OMX_IndexExtCommonStartUnused = OMX_IndexKhronosExtensions + 0x00700000, - - /* Other configurations */ - OMX_IndexExtOtherStartUnused = OMX_IndexKhronosExtensions + 0x00800000, - OMX_IndexConfigAutoFramerateConversion, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigPriority, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexConfigOperatingRate, /**< reference: OMX_PARAM_U32TYPE in Q16 format for video and in Hz for audio */ - - /* Time configurations */ - OMX_IndexExtTimeStartUnused = OMX_IndexKhronosExtensions + 0x00900000, - - OMX_IndexExtMax = 0x7FFFFFFF -} OMX_INDEXEXTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_IndexExt_h */ -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Other.h b/third_party/openmax/include/OMX_Other.h deleted file mode 100644 index caf7f38448..0000000000 --- a/third_party/openmax/include/OMX_Other.h +++ /dev/null @@ -1,337 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Other.h - OpenMax IL version 1.1.2 - * The structures needed by Other components to exchange - * parameters and configuration data with the components. - */ - -#ifndef OMX_Other_h -#define OMX_Other_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration of possible data types which match to multiple domains or no - * domain at all. For types which are vendor specific, a value above - * OMX_OTHER_VENDORTSTART should be used. - */ -typedef enum OMX_OTHER_FORMATTYPE { - OMX_OTHER_FormatTime = 0, /**< Transmission of various timestamps, elapsed time, - time deltas, etc */ - OMX_OTHER_FormatPower, /**< Perhaps used for enabling/disabling power - management, setting clocks? */ - OMX_OTHER_FormatStats, /**< Could be things such as frame rate, frames - dropped, etc */ - OMX_OTHER_FormatBinary, /**< Arbitrary binary data */ - OMX_OTHER_FormatVendorReserved = 1000, /**< Starting value for vendor specific - formats */ - - OMX_OTHER_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_OTHER_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_OTHER_FormatMax = 0x7FFFFFFF -} OMX_OTHER_FORMATTYPE; - -/** - * Enumeration of seek modes. - */ -typedef enum OMX_TIME_SEEKMODETYPE { - OMX_TIME_SeekModeFast = 0, /**< Prefer seeking to an approximation - * of the requested seek position over - * the actual seek position if it - * results in a faster seek. */ - OMX_TIME_SeekModeAccurate, /**< Prefer seeking to the actual seek - * position over an approximation - * of the requested seek position even - * if it results in a slower seek. */ - OMX_TIME_SeekModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_SeekModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_SeekModeMax = 0x7FFFFFFF -} OMX_TIME_SEEKMODETYPE; - -/* Structure representing the seekmode of the component */ -typedef struct OMX_TIME_CONFIG_SEEKMODETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_SEEKMODETYPE eType; /**< The seek mode */ -} OMX_TIME_CONFIG_SEEKMODETYPE; - -/** Structure representing a time stamp used with the following configs - * on the Clock Component (CC): - * - * OMX_IndexConfigTimeCurrentWallTime: query of the CC’s current wall - * time - * OMX_IndexConfigTimeCurrentMediaTime: query of the CC’s current media - * time - * OMX_IndexConfigTimeCurrentAudioReference and - * OMX_IndexConfigTimeCurrentVideoReference: audio/video reference - * clock sending SC its reference time - * OMX_IndexConfigTimeClientStartTime: a Clock Component client sends - * this structure to the Clock Component via a SetConfig on its - * client port when it receives a buffer with - * OMX_BUFFERFLAG_STARTTIME set. It must use the timestamp - * specified by that buffer for nStartTimestamp. - * - * It’s also used with the following config on components in general: - * - * OMX_IndexConfigTimePosition: IL client querying component position - * (GetConfig) or commanding a component to seek to the given location - * (SetConfig) - */ -typedef struct OMX_TIME_CONFIG_TIMESTAMPTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_TICKS nTimestamp; /**< timestamp .*/ -} OMX_TIME_CONFIG_TIMESTAMPTYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_UPDATETYPE { - OMX_TIME_UpdateRequestFulfillment, /**< Update is the fulfillment of a media time request. */ - OMX_TIME_UpdateScaleChanged, /**< Update was generated because the scale chagned. */ - OMX_TIME_UpdateClockStateChanged, /**< Update was generated because the clock state changed. */ - OMX_TIME_UpdateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_UpdateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_UpdateMax = 0x7FFFFFFF -} OMX_TIME_UPDATETYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_REFCLOCKTYPE { - OMX_TIME_RefClockNone, /**< Use no references. */ - OMX_TIME_RefClockAudio, /**< Use references sent through OMX_IndexConfigTimeCurrentAudioReference */ - OMX_TIME_RefClockVideo, /**< Use references sent through OMX_IndexConfigTimeCurrentVideoReference */ - OMX_TIME_RefClockKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_RefClockVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_RefClockMax = 0x7FFFFFFF -} OMX_TIME_REFCLOCKTYPE; - -/** Enumeration of clock states. */ -typedef enum OMX_TIME_CLOCKSTATE { - OMX_TIME_ClockStateRunning, /**< Clock running. */ - OMX_TIME_ClockStateWaitingForStartTime, /**< Clock waiting until the - * prescribed clients emit their - * start time. */ - OMX_TIME_ClockStateStopped, /**< Clock stopped. */ - OMX_TIME_ClockStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_ClockStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_ClockStateMax = 0x7FFFFFFF -} OMX_TIME_CLOCKSTATE; - -/** Structure representing a media time request to the clock component. - * - * A client component sends this structure to the Clock Component via a SetConfig - * on its client port to specify a media timestamp the Clock Component - * should emit. The Clock Component should fulfill the request by sending a - * OMX_TIME_MEDIATIMETYPE when its media clock matches the requested - * timestamp. - * - * The client may require a media time request be fulfilled slightly - * earlier than the media time specified. In this case the client specifies - * an offset which is equal to the difference between wall time corresponding - * to the requested media time and the wall time when it will be - * fulfilled. - * - * A client component may uses these requests and the OMX_TIME_MEDIATIMETYPE to - * time events according to timestamps. If a client must perform an operation O at - * a time T (e.g. deliver a video frame at its corresponding timestamp), it makes a - * media time request at T (perhaps specifying an offset to ensure the request fulfillment - * is a little early). When the clock component passes the resulting OMX_TIME_MEDIATIMETYPE - * structure back to the client component, the client may perform operation O (perhaps having - * to wait a slight amount more time itself as specified by the return values). - */ - -typedef struct OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_PTR pClientPrivate; /**< Client private data to disabiguate this media time - * from others (e.g. the number of the frame to deliver). - * Duplicated in the media time structure that fulfills - * this request. A value of zero is reserved for time scale - * updates. */ - OMX_TICKS nMediaTimestamp; /**< Media timestamp requested.*/ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request should be fulfilled early */ -} OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE; - -/**< Structure sent from the clock component client either when fulfilling - * a media time request or when the time scale has changed. - * - * In the former case the Clock Component fills this structure and times its emission - * to a client component (via the client port) according to the corresponding media - * time request sent by the client. The Clock Component should time the emission to occur - * when the requested timestamp matches the Clock Component's media time but also the - * prescribed offset early. - * - * Upon scale changes the clock component clears the nClientPrivate data, sends the current - * media time and sets the nScale to the new scale via the client port. It emits a - * OMX_TIME_MEDIATIMETYPE to all clients independent of any requests. This allows clients to - * alter processing to accomodate scaling. For instance a video component might skip inter-frames - * in the case of extreme fastforward. Likewise an audio component might add or remove samples - * from an audio frame to scale audio data. - * - * It is expected that some clock components may not be able to fulfill requests - * at exactly the prescribed time. This is acceptable so long as the request is - * fulfilled at least as early as described and not later. This structure provides - * fields the client may use to wait for the remaining time. - * - * The client may use either the nOffset or nWallTimeAtMedia fields to determine the - * wall time until the nMediaTimestamp actually occurs. In the latter case the - * client can get a more accurate value for offset by getting the current wall - * from the cloc component and subtracting it from nWallTimeAtMedia. - */ - -typedef struct OMX_TIME_MEDIATIMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nClientPrivate; /**< Client private data to disabiguate this media time - * from others. Copied from the media time request. - * A value of zero is reserved for time scale updates. */ - OMX_TIME_UPDATETYPE eUpdateType; /**< Reason for the update */ - OMX_TICKS nMediaTimestamp; /**< Media time requested. If no media time was - * requested then this is the current media time. */ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request was actually fulfilled early */ - - OMX_TICKS nWallTimeAtMediaTime; /**< Wall time corresponding to nMediaTimeStamp. - * A client may compare this value to current - * media time obtained from the Clock Component to determine - * the wall time until the media timestamp is really - * current. */ - OMX_S32 xScale; /**< Current media time scale in Q16 format. */ - OMX_TIME_CLOCKSTATE eState; /* Seeking Change. Added 7/12.*/ - /**< State of the media time. */ -} OMX_TIME_MEDIATIMETYPE; - -/** Structure representing the current media time scale factor. Applicable only to clock - * component, other components see scale changes via OMX_TIME_MEDIATIMETYPE buffers sent via - * the clock component client ports. Upon recieving this config the clock component changes - * the rate by which the media time increases or decreases effectively implementing trick modes. - */ -typedef struct OMX_TIME_CONFIG_SCALETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_S32 xScale; /**< This is a value in Q16 format which is used for - * scaling the media time */ -} OMX_TIME_CONFIG_SCALETYPE; - -/** Bits used to identify a clock port. Used in OMX_TIME_CONFIG_CLOCKSTATETYPE’s nWaitMask field */ -#define OMX_CLOCKPORT0 0x00000001 -#define OMX_CLOCKPORT1 0x00000002 -#define OMX_CLOCKPORT2 0x00000004 -#define OMX_CLOCKPORT3 0x00000008 -#define OMX_CLOCKPORT4 0x00000010 -#define OMX_CLOCKPORT5 0x00000020 -#define OMX_CLOCKPORT6 0x00000040 -#define OMX_CLOCKPORT7 0x00000080 - -/** Structure representing the current mode of the media clock. - * IL Client uses this config to change or query the mode of the - * media clock of the clock component. Applicable only to clock - * component. - * - * On a SetConfig if eState is OMX_TIME_ClockStateRunning media time - * starts immediately at the prescribed start time. If - * OMX_TIME_ClockStateWaitingForStartTime the Clock Component ignores - * the given nStartTime and waits for all clients specified in the - * nWaitMask to send starttimes (via - * OMX_IndexConfigTimeClientStartTime). The Clock Component then starts - * the media clock using the earliest start time supplied. */ -typedef struct OMX_TIME_CONFIG_CLOCKSTATETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_TIME_CLOCKSTATE eState; /**< State of the media time. */ - OMX_TICKS nStartTime; /**< Start time of the media time. */ - OMX_TICKS nOffset; /**< Time to offset the media time by - * (e.g. preroll). Media time will be - * reported to be nOffset ticks earlier. - */ - OMX_U32 nWaitMask; /**< Mask of OMX_CLOCKPORT values. */ -} OMX_TIME_CONFIG_CLOCKSTATETYPE; - -/** Structure representing the reference clock currently being used to - * compute media time. IL client uses this config to change or query the - * clock component's active reference clock */ -typedef struct OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_REFCLOCKTYPE eClock; /**< Reference clock used to compute media time */ -} OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE; - -/** Descriptor for setting specifics of power type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_POWERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bEnablePM; /**< Flag to enable Power Management */ -} OMX_OTHER_CONFIG_POWERTYPE; - - -/** Descriptor for setting specifics of stats type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_STATSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - /* what goes here */ -} OMX_OTHER_CONFIG_STATSTYPE; - - -/** - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output other - * path. - */ -typedef struct OMX_OTHER_PORTDEFINITIONTYPE { - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PORTDEFINITIONTYPE; - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_OTHER_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PARAM_PORTFORMATTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_QCOMExtns.h b/third_party/openmax/include/OMX_QCOMExtns.h deleted file mode 100644 index 20917932be..0000000000 --- a/third_party/openmax/include/OMX_QCOMExtns.h +++ /dev/null @@ -1,1888 +0,0 @@ -/*-------------------------------------------------------------------------- -Copyright (c) 2009-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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 __OMX_QCOM_EXTENSIONS_H__ -#define __OMX_QCOM_EXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/*============================================================================ -*//** @file OMX_QCOMExtns.h - This header contains constants and type definitions that specify the - extensions added to the OpenMAX Vendor specific APIs. - -*//*========================================================================*/ - - -/////////////////////////////////////////////////////////////////////////////// -// Include Files -/////////////////////////////////////////////////////////////////////////////// -#include "OMX_Core.h" -#include "OMX_Video.h" - -#define OMX_VIDEO_MAX_HP_LAYERS 6 -/** - * This extension is used to register mapping of a virtual - * address to a physical address. This extension is a parameter - * which can be set using the OMX_SetParameter macro. The data - * pointer corresponding to this extension is - * OMX_QCOM_MemMapEntry. This parameter is a 'write only' - * parameter (Current value cannot be queried using - * OMX_GetParameter macro). - */ -#define OMX_QCOM_EXTN_REGISTER_MMAP "OMX.QCOM.index.param.register_mmap" - -/** - * This structure describes the data pointer corresponding to - * the OMX_QCOM_MMAP_REGISTER_EXTN extension. This parameter - * must be set only 'after' populating a port with a buffer - * using OMX_UseBuffer, wherein the data pointer of the buffer - * corresponds to the virtual address as specified in this - * structure. - */ -struct OMX_QCOM_PARAM_MEMMAPENTRYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - - /** - * The virtual address of memory block - */ - OMX_U64 nVirtualAddress; - - /** - * The physical address corresponding to the virtual address. The physical - * address is contiguous for the entire valid range of the virtual - * address. - */ - OMX_U64 nPhysicalAddress; -}; - -#define QOMX_VIDEO_IntraRefreshRandom (OMX_VIDEO_IntraRefreshVendorStartUnused + 0) - -/* This error event is used for H.264 long-term reference (LTR) encoding. - * When IL client specifies an LTR frame with its identifier via - * OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE to the encoder, if the specified - * LTR frame can not be located by the encoder in its LTR list, the encoder - * issues this error event to IL client to notify the failure of LTRUse config. - */ -#define QOMX_ErrorLTRUseFailed (OMX_ErrorVendorStartUnused + 1) - -#define QOMX_VIDEO_BUFFERFLAG_BFRAME 0x00100000 - -#define QOMX_VIDEO_BUFFERFLAG_EOSEQ 0x00200000 - -#define QOMX_VIDEO_BUFFERFLAG_MBAFF 0x00400000 - -#define QOMX_VIDEO_BUFFERFLAG_CANCEL 0x00800000 - -#define OMX_QCOM_PORTDEFN_EXTN "OMX.QCOM.index.param.portdefn" -/* Allowed APIs on the above Index: OMX_GetParameter() and OMX_SetParameter() */ - -typedef enum OMX_QCOMMemoryRegion -{ - OMX_QCOM_MemRegionInvalid, - OMX_QCOM_MemRegionEBI1, - OMX_QCOM_MemRegionSMI, - OMX_QCOM_MemRegionMax = 0X7FFFFFFF -} OMX_QCOMMemoryRegion; - -typedef enum OMX_QCOMCacheAttr -{ - OMX_QCOM_CacheAttrNone, - OMX_QCOM_CacheAttrWriteBack, - OMX_QCOM_CacheAttrWriteThrough, - OMX_QCOM_CacheAttrMAX = 0X7FFFFFFF -} OMX_QCOMCacheAttr; - -typedef struct OMX_QCOMRectangle -{ - OMX_S32 x; - OMX_S32 y; - OMX_S32 dx; - OMX_S32 dy; -} OMX_QCOMRectangle; - -/** OMX_QCOMFramePackingFormat - * Input or output buffer format - */ -typedef enum OMX_QCOMFramePackingFormat -{ - /* 0 - unspecified - */ - OMX_QCOM_FramePacking_Unspecified, - - /* 1 - Partial frames may be present OMX IL 1.1.1 Figure 2-10: - * Case 1??Each Buffer Filled In Whole or In Part - */ - OMX_QCOM_FramePacking_Arbitrary, - - /* 2 - Multiple complete frames per buffer (integer number) - * OMX IL 1.1.1 Figure 2-11: Case 2—Each Buffer Filled with - * Only Complete Frames of Data - */ - OMX_QCOM_FramePacking_CompleteFrames, - - /* 3 - Only one complete frame per buffer, no partial frame - * OMX IL 1.1.1 Figure 2-12: Case 3—Each Buffer Filled with - * Only One Frame of Compressed Data. Usually at least one - * complete unit of data will be delivered in a buffer for - * uncompressed data formats. - */ - OMX_QCOM_FramePacking_OnlyOneCompleteFrame, - - /* 4 - Only one complete subframe per buffer, no partial subframe - * Example: In H264, one complete NAL per buffer, where one frame - * can contatin multiple NAL - */ - OMX_QCOM_FramePacking_OnlyOneCompleteSubFrame, - - OMX_QCOM_FramePacking_MAX = 0X7FFFFFFF -} OMX_QCOMFramePackingFormat; - -typedef struct OMX_QCOM_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - - /** Platform specific memory region EBI1, SMI, etc.,*/ - OMX_QCOMMemoryRegion nMemRegion; - - OMX_QCOMCacheAttr nCacheAttr; /** Cache attributes */ - - /** Input or output buffer format */ - OMX_U32 nFramePackingFormat; - -} OMX_QCOM_PARAM_PORTDEFINITIONTYPE; - -typedef struct OMX_QCOM_VIDEO_PARAM_QPRANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 minQP; - OMX_U32 maxQP; -} OMX_QCOM_VIDEO_PARAM_QPRANGETYPE; - -#define OMX_QCOM_PLATFORMPVT_EXTN "OMX.QCOM.index.param.platformprivate" -/** Allowed APIs on the above Index: OMX_SetParameter() */ - -typedef enum OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE -{ - /** Enum for PMEM information */ - OMX_QCOM_PLATFORM_PRIVATE_PMEM = 0x1 -} OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE; - -/** IL client will set the following structure. A failure - * code will be returned if component does not support the - * value provided for 'type'. - */ -struct OMX_QCOM_PLATFORMPRIVATE_EXTN -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX spec version information */ - OMX_U32 nPortIndex; /** Port number on which usebuffer extn is applied */ - - /** Type of extensions should match an entry from - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; -}; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO -{ - /** pmem file descriptor */ - unsigned long pmem_fd; - /** Offset from pmem device base address */ - OMX_U32 offset; - OMX_U32 size; - OMX_U32 mapped_size; - OMX_PTR buffer; -}OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_ENTRY -{ - /** Entry type */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; - - /** Pointer to platform specific entry */ - OMX_PTR entry; -}OMX_QCOM_PLATFORM_PRIVATE_ENTRY; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_LIST -{ - /** Number of entries */ - OMX_U32 nEntries; - - /** Pointer to array of platform specific entries * - * Contiguous block of OMX_QCOM_PLATFORM_PRIVATE_ENTRY element - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY* entryList; -}OMX_QCOM_PLATFORM_PRIVATE_LIST; - -#define OMX_QCOM_FRAME_PACKING_FORMAT "OMX.QCOM.index.param.framepackfmt" -/* Allowed API call: OMX_GetParameter() */ -/* IL client can use this index to rerieve the list of frame formats * - * supported by the component */ - -typedef struct OMX_QCOM_FRAME_PACKINGFORMAT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOMFramePackingFormat eframePackingFormat; -} OMX_QCOM_FRAME_PACKINGFORMAT_TYPE; - - -/** - * Following is the enum for color formats supported on Qualcomm - * MSMs YVU420SemiPlanar color format is not defined in OpenMAX - * 1.1.1 and prior versions of OpenMAX specification. - */ - -enum OMX_QCOM_COLOR_FORMATTYPE -{ - -/** YVU420SemiPlanar: YVU planar format, organized with a first - * plane containing Y pixels, and a second plane containing - * interleaved V and U pixels. V and U pixels are sub-sampled - * by a factor of two both horizontally and vertically. - */ - QOMX_COLOR_FormatYVU420SemiPlanar = 0x7FA30C00, - QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed, - QOMX_COLOR_Format32bitRGBA8888, - QOMX_COLOR_Format32bitRGBA8888Compressed, - QOMX_COLOR_FormatAndroidOpaque = (OMX_COLOR_FORMATTYPE) OMX_COLOR_FormatVendorStartUnused + 0x789, -}; - -enum OMX_QCOM_VIDEO_CODINGTYPE -{ -/** Codecs support by qualcomm which are not listed in OMX 1.1.x - * spec - * */ - OMX_QCOM_VIDEO_CodingVC1 = 0x7FA30C00 , - OMX_QCOM_VIDEO_CodingWMV9 = 0x7FA30C01, - QOMX_VIDEO_CodingDivx = 0x7FA30C02, /**< Value when coding is Divx */ - QOMX_VIDEO_CodingSpark = 0x7FA30C03, /**< Value when coding is Sorenson Spark */ - QOMX_VIDEO_CodingVp = 0x7FA30C04, - QOMX_VIDEO_CodingVp8 = OMX_VIDEO_CodingVP8, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingHevc = OMX_VIDEO_CodingHEVC, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingMVC = 0x7FA30C07, - QOMX_VIDEO_CodingVp9 = OMX_VIDEO_CodingVP9, /**< keeping old enum for backwards compatibility*/ -}; - -enum OMX_QCOM_EXTN_INDEXTYPE -{ - /** Qcom proprietary extension index list */ - - /* "OMX.QCOM.index.param.register_mmap" */ - OMX_QcomIndexRegmmap = 0x7F000000, - - /* "OMX.QCOM.index.param.platformprivate" */ - OMX_QcomIndexPlatformPvt = 0x7F000001, - - /* "OMX.QCOM.index.param.portdefn" */ - OMX_QcomIndexPortDefn = 0x7F000002, - - /* "OMX.QCOM.index.param.framepackingformat" */ - OMX_QcomIndexPortFramePackFmt = 0x7F000003, - - /*"OMX.QCOM.index.param.Interlaced */ - OMX_QcomIndexParamInterlaced = 0x7F000004, - - /*"OMX.QCOM.index.config.interlaceformat */ - OMX_QcomIndexConfigInterlaced = 0x7F000005, - - /*"OMX.QCOM.index.param.syntaxhdr" */ - QOMX_IndexParamVideoSyntaxHdr = 0x7F000006, - - /*"OMX.QCOM.index.config.intraperiod" */ - QOMX_IndexConfigVideoIntraperiod = 0x7F000007, - - /*"OMX.QCOM.index.config.randomIntrarefresh" */ - QOMX_IndexConfigVideoIntraRefresh = 0x7F000008, - - /*"OMX.QCOM.index.config.video.TemporalSpatialTradeOff" */ - QOMX_IndexConfigVideoTemporalSpatialTradeOff = 0x7F000009, - - /*"OMX.QCOM.index.param.video.EncoderMode" */ - QOMX_IndexParamVideoEncoderMode = 0x7F00000A, - - /*"OMX.QCOM.index.param.Divxtype */ - OMX_QcomIndexParamVideoDivx = 0x7F00000B, - - /*"OMX.QCOM.index.param.Sparktype */ - OMX_QcomIndexParamVideoSpark = 0x7F00000C, - - /*"OMX.QCOM.index.param.Vptype */ - OMX_QcomIndexParamVideoVp = 0x7F00000D, - - OMX_QcomIndexQueryNumberOfVideoDecInstance = 0x7F00000E, - - OMX_QcomIndexParamVideoSyncFrameDecodingMode = 0x7F00000F, - - OMX_QcomIndexParamVideoDecoderPictureOrder = 0x7F000010, - - /* "OMX.QCOM.index.config.video.FramePackingInfo" */ - OMX_QcomIndexConfigVideoFramePackingArrangement = 0x7F000011, - - OMX_QcomIndexParamConcealMBMapExtraData = 0x7F000012, - - OMX_QcomIndexParamFrameInfoExtraData = 0x7F000013, - - OMX_QcomIndexParamInterlaceExtraData = 0x7F000014, - - OMX_QcomIndexParamH264TimeInfo = 0x7F000015, - - OMX_QcomIndexParamIndexExtraDataType = 0x7F000016, - - OMX_GoogleAndroidIndexEnableAndroidNativeBuffers = 0x7F000017, - - OMX_GoogleAndroidIndexUseAndroidNativeBuffer = 0x7F000018, - - OMX_GoogleAndroidIndexGetAndroidNativeBufferUsage = 0x7F000019, - - /*"OMX.QCOM.index.config.video.QPRange" */ - OMX_QcomIndexConfigVideoQPRange = 0x7F00001A, - - /*"OMX.QCOM.index.param.EnableTimeStampReoder"*/ - OMX_QcomIndexParamEnableTimeStampReorder = 0x7F00001B, - - /*"OMX.google.android.index.storeMetaDataInBuffers"*/ - OMX_QcomIndexParamVideoMetaBufferMode = 0x7F00001C, - - /*"OMX.google.android.index.useAndroidNativeBuffer2"*/ - OMX_GoogleAndroidIndexUseAndroidNativeBuffer2 = 0x7F00001D, - - /*"OMX.QCOM.index.param.VideoMaxAllowedBitrateCheck"*/ - OMX_QcomIndexParamVideoMaxAllowedBitrateCheck = 0x7F00001E, - - OMX_QcomIndexEnableSliceDeliveryMode = 0x7F00001F, - - /* "OMX.QCOM.index.param.video.ExtnUserExtraData" */ - OMX_QcomIndexEnableExtnUserData = 0x7F000020, - - /*"OMX.QCOM.index.param.video.EnableSmoothStreaming"*/ - OMX_QcomIndexParamEnableSmoothStreaming = 0x7F000021, - - /*"OMX.QCOM.index.param.video.QPRange" */ - OMX_QcomIndexParamVideoQPRange = 0x7F000022, - - OMX_QcomIndexEnableH263PlusPType = 0x7F000023, - - /*"OMX.QCOM.index.param.video.LTRCountRangeSupported"*/ - QOMX_IndexParamVideoLTRCountRangeSupported = 0x7F000024, - - /*"OMX.QCOM.index.param.video.LTRMode"*/ - QOMX_IndexParamVideoLTRMode = 0x7F000025, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - QOMX_IndexParamVideoLTRCount = 0x7F000026, - - /*"OMX.QCOM.index.config.video.LTRPeriod"*/ - QOMX_IndexConfigVideoLTRPeriod = 0x7F000027, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - QOMX_IndexConfigVideoLTRUse = 0x7F000028, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - QOMX_IndexConfigVideoLTRMark = 0x7F000029, - - /* OMX.google.android.index.prependSPSPPSToIDRFrames */ - OMX_QcomIndexParamSequenceHeaderWithIDR = 0x7F00002A, - - OMX_QcomIndexParamH264AUDelimiter = 0x7F00002B, - - OMX_QcomIndexParamVideoDownScalar = 0x7F00002C, - - /* "OMX.QCOM.index.param.video.FramePackingExtradata" */ - OMX_QcomIndexParamVideoFramePackingExtradata = 0x7F00002D, - - /* "OMX.QCOM.index.config.activeregiondetection" */ - OMX_QcomIndexConfigActiveRegionDetection = 0x7F00002E, - - /* "OMX.QCOM.index.config.activeregiondetectionstatus" */ - OMX_QcomIndexConfigActiveRegionDetectionStatus = 0x7F00002F, - - /* "OMX.QCOM.index.config.scalingmode" */ - OMX_QcomIndexConfigScalingMode = 0x7F000030, - - /* "OMX.QCOM.index.config.noisereduction" */ - OMX_QcomIndexConfigNoiseReduction = 0x7F000031, - - /* "OMX.QCOM.index.config.imageenhancement" */ - OMX_QcomIndexConfigImageEnhancement = 0x7F000032, - - /* google smooth-streaming support */ - OMX_QcomIndexParamVideoAdaptivePlaybackMode = 0x7F000033, - - /* H.264 MVC codec index */ - QOMX_IndexParamVideoMvc = 0x7F000034, - - /* "OMX.QCOM.index.param.video.QPExtradata" */ - OMX_QcomIndexParamVideoQPExtraData = 0x7F000035, - - /* "OMX.QCOM.index.param.video.InputBitsInfoExtradata" */ - OMX_QcomIndexParamVideoInputBitsInfoExtraData = 0x7F000036, - - /* VP8 Hierarchical P support */ - OMX_QcomIndexHierarchicalStructure = 0x7F000037, - - OMX_QcomIndexParamPerfLevel = 0x7F000038, - - OMX_QcomIndexParamH264VUITimingInfo = 0x7F000039, - - OMX_QcomIndexParamPeakBitrate = 0x7F00003A, - - /* Enable InitialQP index */ - QOMX_IndexParamVideoInitialQp = 0x7F00003B, - - OMX_QcomIndexParamSetMVSearchrange = 0x7F00003C, - - OMX_QcomIndexConfigPerfLevel = 0x7F00003D, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - OMX_QcomIndexParamVideoLTRCount = QOMX_IndexParamVideoLTRCount, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - OMX_QcomIndexConfigVideoLTRUse = QOMX_IndexConfigVideoLTRUse, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - OMX_QcomIndexConfigVideoLTRMark = QOMX_IndexConfigVideoLTRMark, - - /*"OMX.QCOM.index.param.video.CustomBufferSize"*/ - OMX_QcomIndexParamVideoCustomBufferSize = 0x7F00003E, - - /* Max Hierarchical P layers */ - OMX_QcomIndexMaxHierarchicallayers = 0x7F000041, - - /* Set Encoder Performance Index */ - OMX_QcomIndexConfigVideoVencPerfMode = 0x7F000042, - - /* Set Hybrid Hier-p layers */ - OMX_QcomIndexParamVideoHybridHierpMode = 0x7F000043, - - OMX_QcomIndexFlexibleYUVDescription = 0x7F000044, - - /* Vpp Hqv Control Type */ - OMX_QcomIndexParamVppHqvControl = 0x7F000045, - - /* Enable VPP */ - OMX_QcomIndexParamEnableVpp = 0x7F000046, - - /* MBI statistics mode */ - OMX_QcomIndexParamMBIStatisticsMode = 0x7F000047, - - /* Set PictureTypeDecode */ - OMX_QcomIndexConfigPictureTypeDecode = 0x7F000048, - - OMX_QcomIndexConfigH264EntropyCodingCabac = 0x7F000049, - - /* "OMX.QCOM.index.param.video.InputBatch" */ - OMX_QcomIndexParamBatchSize = 0x7F00004A, - - OMX_QcomIndexConfigNumHierPLayers = 0x7F00004B, - - OMX_QcomIndexConfigRectType = 0x7F00004C, - - OMX_QcomIndexConfigBaseLayerId = 0x7F00004E, - - OMX_QcomIndexParamDriverVersion = 0x7F00004F, - - OMX_QcomIndexConfigQp = 0x7F000050, - - OMX_QcomIndexParamVencAspectRatio = 0x7F000051, - - OMX_QTIIndexParamVQZipSEIExtraData = 0x7F000052, - - /* Enable VQZIP SEI NAL type */ - OMX_QTIIndexParamVQZIPSEIType = 0x7F000053, - - OMX_QTIIndexParamPassInputBufferFd = 0x7F000054, - - /* Set Prefer-adaptive playback*/ - /* "OMX.QTI.index.param.video.PreferAdaptivePlayback" */ - OMX_QTIIndexParamVideoPreferAdaptivePlayback = 0x7F000055, - - /* Set time params */ - OMX_QTIIndexConfigSetTimeData = 0x7F000056, - /* Force Compressed format for DPB when resolution <=1080p - * and OPB is cpu_access */ - /* OMX.QTI.index.param.video.ForceCompressedForDPB */ - OMX_QTIIndexParamForceCompressedForDPB = 0x7F000057, - - /* Enable ROI info */ - OMX_QTIIndexParamVideoEnableRoiInfo = 0x7F000058, - - /* Configure ROI info */ - OMX_QTIIndexConfigVideoRoiInfo = 0x7F000059, - - /* Set Low Latency Mode */ - OMX_QTIIndexParamLowLatencyMode = 0x7F00005A, - - /* Force OPB to UnCompressed mode */ - OMX_QTIIndexParamForceUnCompressedForOPB = 0x7F00005B, - -}; - -/** -* This is custom extension to configure Low Latency Mode. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* bLowLatencyMode : Enable/Disable Low Latency mode -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bLowLatencyMode; -} QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE; - -/** -* This is custom extension to configure Encoder Aspect Ratio. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nSARWidth : Horizontal aspect size -* nSARHeight : Vertical aspect size -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_SAR -{ - OMX_U32 nSize; - OMX_U32 nVersion; - OMX_U32 nSARWidth; - OMX_U32 nSARHeight; -} QOMX_EXTNINDEX_VIDEO_VENC_SAR; - -/** -* This is custom extension to configure Hier-p layers. -* This mode configures Hier-p layers dynamically. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nNumHierLayers: Set the number of Hier-p layers for the session -* - This should be less than the MAX Hier-P -* layers set for the session. -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nNumHierLayers; -} QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS; - - -/** -* This is custom extension to configure Hybrid Hier-p settings. -* This mode is different from enabling Hier-p mode. This -* property enables Hier-p encoding with LTR referencing in each -* sub-GOP. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nKeyFrameInterval : Indicates the I frame interval -* nHpLayers : Set the number of Hier-p layers for the session -* - This should be <= 6. (1 Base layer + -* 5 Enhancement layers) -* nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS] : Bitrate to -* be set for each enhancement layer -* nMinQuantizer : minimum session QP -* nMaxQuantizer : Maximun session QP -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nKeyFrameInterval; - OMX_U32 nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS]; - OMX_U32 nMinQuantizer; - OMX_U32 nMaxQuantizer; - OMX_U32 nHpLayers; -} QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE; - -/** - * Encoder Performance Mode. This structure is used to set - * performance mode or power save mode when encoding. The search - * range is modified to save power or improve quality. - * - * STRUCT MEMBERS: - * OMX_U32 nPerfMode : Performance mode: - * 1: MAX_QUALITY - * 2: POWER_SAVE - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_PERFMODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPerfMode; -} QOMX_EXTNINDEX_VIDEO_PERFMODE; - -/** - * Initial QP parameter. This structure is used to enable - * vendor specific extension to let client enable setting - * initial QP values to I P B Frames - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * OMX_U32 nQpI : First Iframe QP - * OMX_U32 nQpP : First Pframe QP - * OMX_U32 nQpB : First Bframe QP - * OMX_U32 bEnableInitQp : Bit field indicating which frame type(s) shall - * use the specified initial QP. - * Bit 0: Enable initial QP for I/IDR - * and use value specified in nInitQpI - * Bit 1: Enable initial QP for P - * and use value specified in nInitQpP - * Bit 2: Enable initial QP for B - * and use value specified in nInitQpB - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_INITIALQP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; - OMX_U32 bEnableInitQp; -} QOMX_EXTNINDEX_VIDEO_INITIALQP; - -/** - * Extension index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required flags and data, if any. - * The format of flags and data being passed is known to - * the client and component apriori. - * - * STRUCT MEMBERS: - * nSize : Size of Structure plus pData size - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * bEnable : Extension index enable (1) or disable (0) - * nFlags : Extension index flags, if any - * nDataSize : Size of the extension index data to follow - * pData : Extension index data, if present. - */ -typedef struct QOMX_EXTNINDEX_PARAMTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_U32 nFlags; - OMX_U32 nDataSize; - OMX_PTR pData; -} QOMX_EXTNINDEX_PARAMTYPE; - -/** - * Range index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required minimum and maximum values - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nMin : Minimum value - * nMax : Maximum value - * nSteSize : Step size - */ -typedef struct QOMX_EXTNINDEX_RANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nMin; - OMX_S32 nMax; - OMX_S32 nStepSize; -} QOMX_EXTNINDEX_RANGETYPE; - -/** - * Specifies LTR mode types. - */ -typedef enum QOMX_VIDEO_LTRMODETYPE -{ - QOMX_VIDEO_LTRMode_Disable = 0x0, /**< LTR encoding is disabled */ - QOMX_VIDEO_LTRMode_Manual = 0x1, /**< In this mode, IL client configures - ** the encoder the LTR count and manually - ** controls the marking and use of LTR - ** frames during video encoding. - */ - QOMX_VIDEO_LTRMode_Auto = 0x2, /**< In this mode, IL client configures - ** the encoder the LTR count and LTR - ** period. The encoder marks LTR frames - ** automatically based on the LTR period - ** during video encoding. IL client controls - ** the use of LTR frames. - */ - QOMX_VIDEO_LTRMode_MAX = 0x7FFFFFFF /** Maximum LTR Mode type */ -} QOMX_VIDEO_LTRMODETYPE; - -/** - * LTR mode index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR mode information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * eLTRMode : Specifies the LTR mode used in encoder - */ -typedef struct QOMX_VIDEO_PARAM_LTRMODE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_LTRMODETYPE eLTRMode; -} QOMX_VIDEO_PARAM_LTRMODE_TYPE; - -/** - * LTR count index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR count information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nCount : Specifies the number of LTR frames stored in the - * encoder component - */ -typedef struct QOMX_VIDEO_PARAM_LTRCOUNT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nCount; -} QOMX_VIDEO_PARAM_LTRCOUNT_TYPE; - - -/** - * This should be used with OMX_QcomIndexParamVideoLTRCount extension. - */ -typedef QOMX_VIDEO_PARAM_LTRCOUNT_TYPE OMX_QCOM_VIDEO_PARAM_LTRCOUNT_TYPE; - -/** - * LTR period index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR period information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nFrames : Specifies the number of frames between two consecutive - * LTR frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE; - -/** - * Marks the next encoded frame as an LTR frame. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be marked - * as reference frame for encoding subsequent frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRMARK_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; -} QOMX_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRMark extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRMARK_TYPE OMX_QCOM_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * Specifies an LTR frame to encode subsequent frames. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be used - as reference frame for encoding subsequent frames. - * nFrames : Specifies the number of subsequent frames to be - encoded using the LTR frame with its identifier - nID as reference frame. Short-term reference frames - will be used thereafter. The value of 0xFFFFFFFF - indicates that all subsequent frames will be - encodedusing this LTR frame as reference frame. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRUSE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRUse extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRUSE_TYPE OMX_QCOM_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * Enumeration used to define the video encoder modes - * - * ENUMS: - * EncoderModeDefault : Default video recording mode. - * All encoder settings made through - * OMX_SetParameter/OMX_SetConfig are applied. No - * parameter is overridden. - * EncoderModeMMS : Video recording mode for MMS (Multimedia Messaging - * Service). This mode is similar to EncoderModeDefault - * except that here the Rate control mode is overridden - * internally and set as a variant of variable bitrate with - * variable frame rate. After this mode is set if the IL - * client tries to set OMX_VIDEO_CONTROLRATETYPE via - * OMX_IndexParamVideoBitrate that would be rejected. For - * this, client should set mode back to EncoderModeDefault - * first and then change OMX_VIDEO_CONTROLRATETYPE. - */ -typedef enum QOMX_VIDEO_ENCODERMODETYPE -{ - QOMX_VIDEO_EncoderModeDefault = 0x00, - QOMX_VIDEO_EncoderModeMMS = 0x01, - QOMX_VIDEO_EncoderModeMax = 0x7FFFFFFF -} QOMX_VIDEO_ENCODERMODETYPE; - -/** - * This structure is used to set the video encoder mode. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nMode : defines the video encoder mode - */ -typedef struct QOMX_VIDEO_PARAM_ENCODERMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_ENCODERMODETYPE nMode; -} QOMX_VIDEO_PARAM_ENCODERMODETYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_SYNTAXHDRTYPE extension. This parameter can be queried - * during the loaded state. - */ - -typedef struct QOMX_VIDEO_SYNTAXHDRTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBytes; /** The number of bytes filled in to the buffer */ - OMX_U8 data[1]; /** Buffer to store the header information */ -} QOMX_VIDEO_SYNTAXHDRTYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_TEMPORALSPATIALTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for setting MaxQP from the application. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_TEMPORALSPATIALTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nTSFactor; /** Temoral spatial tradeoff factor value in 0-100 */ -} QOMX_VIDEO_TEMPORALSPATIALTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_INTRAPERIODTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_INTRAPERIODTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nIDRPeriod; /** This specifies coding a frame as IDR after every nPFrames - of intra frames. If this parameter is set to 0, only the - first frame of the encode session is an IDR frame. This - field is ignored for non-AVC codecs and is used only for - codecs that support IDR Period */ - OMX_U32 nPFrames; /** The number of "P" frames between two "I" frames */ - OMX_U32 nBFrames; /** The number of "B" frames between two "I" frames */ -} QOMX_VIDEO_INTRAPERIODTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is used for the buffer negotiation - * with other clients. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBufferOccupancy; /** The number of bytes to be set for the buffer occupancy */ -} OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily used for the dynamic/random - * intrarefresh. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nRirMBs; /** The number of MBs to be set for intrarefresh */ -} OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE; - - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_QPRANGE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for the min/max QP to be set from the application. This - * is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_QPRANGE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nMinQP; /** The number for minimum quantization parameter */ - OMX_U32 nMaxQP; /** The number for maximum quantization parameter */ -} OMX_QCOM_VIDEO_CONFIG_QPRANGE; - -/** - * This structure describes the parameters for the - * OMX_QcomIndexParamH264AUDelimiter extension. It enables/disables - * the AU delimiters in the H264 stream, which is used by WFD. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_H264_AUD -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_CONFIG_H264_AUD; - -typedef enum QOMX_VIDEO_PERF_LEVEL -{ - OMX_QCOM_PerfLevelNominal, - OMX_QCOM_PerfLevelTurbo -} QOMX_VIDEO_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_PARAM_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL; - -typedef enum QOMX_VIDEO_PICTURE_TYPE_DECODE -{ - OMX_QCOM_PictypeDecode_IPB, - OMX_QCOM_PictypeDecode_I -} QOMX_VIDEO_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPictureTypeDecode extension. It - * will set the picture type decode specified by eDecodeType. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PICTURE_TYPE_DECODE eDecodeType; /** Decode type */ -} OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamH264VUITimingInfo extension. It - * will enable/disable the VUI timing info. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamVQZIPSEIType extension. It - * will enable/disable the VQZIP SEI info. - */ -typedef struct OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPeakBitrate extension. It will - * set the peak bitrate specified by nPeakBitrate. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPeakBitrate; /** Peak bitrate value */ -} OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceCompressedForDPB extension. Enabling - * this extension will force the split mode DPB(compressed)/OPB(Linear) - * for all resolutions.On some chipsets preferred mode would be combined - * Linear for both DPB/OPB to save memory. For example on 8996 preferred mode - * would be combined linear for resolutions <= 1080p . - * Enabling this might save power but with the cost - * of increased memory i.e almost double the number on output YUV buffers. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceUnCompressedForOPB extension. Enabling this - * extension will force the OPB to be linear for the current video session. - * If this property is not set, then the OPB will be set to linear or compressed - * based on resolution selected and/or if cpu access is requested on the - * OPB buffer. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE { - OMX_U32 nSize; /** Sizeo f the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE; - -typedef struct OMX_VENDOR_EXTRADATATYPE { - OMX_U32 nPortIndex; - OMX_U32 nDataSize; - OMX_U8 *pData; // cdata (codec_data/extradata) -} OMX_VENDOR_EXTRADATATYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_VENDOR_VIDEOFRAMERATE extension. This parameter can be set - * dynamically during any state except the state invalid. This is - * used for frame rate to be set from the application. This - * is set on the in port. - */ -typedef struct OMX_VENDOR_VIDEOFRAMERATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nFps; /** Frame rate value */ - OMX_BOOL bEnabled; /** Flag to enable or disable client's frame rate value */ -} OMX_VENDOR_VIDEOFRAMERATE; - -typedef enum OMX_INDEXVENDORTYPE { - OMX_IndexVendorFileReadInputFilename = 0xFF000001, - OMX_IndexVendorParser3gpInputFilename = 0xFF000002, - OMX_IndexVendorVideoExtraData = 0xFF000003, - OMX_IndexVendorAudioExtraData = 0xFF000004, - OMX_IndexVendorVideoFrameRate = 0xFF000005, -} OMX_INDEXVENDORTYPE; - -typedef enum OMX_QCOM_VC1RESOLUTIONTYPE -{ - OMX_QCOM_VC1_PICTURE_RES_1x1, - OMX_QCOM_VC1_PICTURE_RES_2x1, - OMX_QCOM_VC1_PICTURE_RES_1x2, - OMX_QCOM_VC1_PICTURE_RES_2x2 -} OMX_QCOM_VC1RESOLUTIONTYPE; - -typedef enum OMX_QCOM_INTERLACETYPE -{ - OMX_QCOM_InterlaceFrameProgressive, - OMX_QCOM_InterlaceInterleaveFrameTopFieldFirst, - OMX_QCOM_InterlaceInterleaveFrameBottomFieldFirst, - OMX_QCOM_InterlaceFrameTopFieldFirst, - OMX_QCOM_InterlaceFrameBottomFieldFirst, - OMX_QCOM_InterlaceFieldTop, - OMX_QCOM_InterlaceFieldBottom -}OMX_QCOM_INTERLACETYPE; - -typedef struct OMX_QCOM_PARAM_VIDEO_INTERLACETYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_BOOL bInterlace; /** Interlace content **/ -}OMX_QCOM_PARAM_VIDEO_INTERLACETYPE; - -typedef struct OMX_QCOM_CONFIG_INTERLACETYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOM_INTERLACETYPE eInterlaceType; -}OMX_QCOM_CONFIG_INTERLACETYPE; - -#define MAX_PAN_SCAN_WINDOWS 4 - -typedef struct OMX_QCOM_PANSCAN -{ - OMX_U32 numWindows; - OMX_QCOMRectangle window[MAX_PAN_SCAN_WINDOWS]; -} OMX_QCOM_PANSCAN; - -typedef struct OMX_QCOM_ASPECT_RATIO -{ - OMX_U32 aspectRatioX; - OMX_U32 aspectRatioY; -} OMX_QCOM_ASPECT_RATIO; - -typedef struct OMX_QCOM_DISPLAY_ASPECT_RATIO -{ - OMX_U32 displayVerticalSize; - OMX_U32 displayHorizontalSize; -} OMX_QCOM_DISPLAY_ASPECT_RATIO; - -typedef struct OMX_QCOM_FRAME_PACK_ARRANGEMENT -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 id; - OMX_U32 cancel_flag; - OMX_U32 type; - OMX_U32 quincunx_sampling_flag; - OMX_U32 content_interpretation_type; - OMX_U32 spatial_flipping_flag; - OMX_U32 frame0_flipped_flag; - OMX_U32 field_views_flag; - OMX_U32 current_frame_is_frame0_flag; - OMX_U32 frame0_self_contained_flag; - OMX_U32 frame1_self_contained_flag; - OMX_U32 frame0_grid_position_x; - OMX_U32 frame0_grid_position_y; - OMX_U32 frame1_grid_position_x; - OMX_U32 frame1_grid_position_y; - OMX_U32 reserved_byte; - OMX_U32 repetition_period; - OMX_U32 extension_flag; -} OMX_QCOM_FRAME_PACK_ARRANGEMENT; - -typedef struct OMX_QCOM_EXTRADATA_QP -{ - OMX_U32 nQP; -} OMX_QCOM_EXTRADATA_QP; - -typedef struct OMX_QCOM_EXTRADATA_BITS_INFO -{ - OMX_U32 header_bits; - OMX_U32 frame_bits; -} OMX_QCOM_EXTRADATA_BITS_INFO; - -typedef struct OMX_QCOM_EXTRADATA_USERDATA { - OMX_U32 type; - OMX_U32 data[1]; -} OMX_QCOM_EXTRADATA_USERDATA; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEINFO -{ - // common frame meta data. interlace related info removed - OMX_VIDEO_PICTURETYPE ePicType; - OMX_QCOM_INTERLACETYPE interlaceType; - OMX_QCOM_PANSCAN panScan; - OMX_QCOM_ASPECT_RATIO aspectRatio; - OMX_QCOM_DISPLAY_ASPECT_RATIO displayAspectRatio; - OMX_U32 nConcealedMacroblocks; - OMX_U32 nFrameRate; - OMX_TICKS nTimeStamp; -} OMX_QCOM_EXTRADATA_FRAMEINFO; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEDIMENSION -{ - /** Frame Dimensions added to each YUV buffer */ - OMX_U32 nDecWidth; /** Width rounded to multiple of 16 */ - OMX_U32 nDecHeight; /** Height rounded to multiple of 16 */ - OMX_U32 nActualWidth; /** Actual Frame Width */ - OMX_U32 nActualHeight; /** Actual Frame Height */ - -} OMX_QCOM_EXTRADATA_FRAMEDIMENSION; - -typedef struct OMX_QCOM_H264EXTRADATA -{ - OMX_U64 seiTimeStamp; -} OMX_QCOM_H264EXTRADATA; - -typedef struct OMX_QCOM_VC1EXTRADATA -{ - OMX_U32 nVC1RangeY; - OMX_U32 nVC1RangeUV; - OMX_QCOM_VC1RESOLUTIONTYPE eVC1PicResolution; -} OMX_QCOM_VC1EXTRADATA; - -typedef union OMX_QCOM_EXTRADATA_CODEC_DATA -{ - OMX_QCOM_H264EXTRADATA h264ExtraData; - OMX_QCOM_VC1EXTRADATA vc1ExtraData; -} OMX_QCOM_EXTRADATA_CODEC_DATA; - -typedef struct OMX_QCOM_EXTRADATA_MBINFO -{ - OMX_U32 nFormat; - OMX_U32 nDataSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_MBINFO; - -typedef struct OMX_QCOM_EXTRADATA_VQZIPSEI { - OMX_U32 nSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_VQZIPSEI; - -typedef struct OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableRoiInfo; -} OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO; - -typedef struct OMX_QTI_VIDEO_CONFIG_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nUpperQpOffset; - OMX_S32 nLowerQpOffset; - OMX_BOOL bUseRoiInfo; - OMX_S32 nRoiMBInfoSize; - OMX_PTR pRoiMBInfo; -} OMX_QTI_VIDEO_CONFIG_ROIINFO; - -typedef enum OMX_QCOM_EXTRADATATYPE -{ - OMX_ExtraDataFrameInfo = 0x7F000001, - OMX_ExtraDataH264 = 0x7F000002, - OMX_ExtraDataVC1 = 0x7F000003, - OMX_ExtraDataFrameDimension = 0x7F000004, - OMX_ExtraDataVideoEncoderSliceInfo = 0x7F000005, - OMX_ExtraDataConcealMB = 0x7F000006, - OMX_ExtraDataInterlaceFormat = 0x7F000007, - OMX_ExtraDataPortDef = 0x7F000008, - OMX_ExtraDataMP2ExtnData = 0x7F000009, - OMX_ExtraDataMP2UserData = 0x7F00000a, - OMX_ExtraDataVideoLTRInfo = 0x7F00000b, - OMX_ExtraDataFramePackingArrangement = 0x7F00000c, - OMX_ExtraDataQP = 0x7F00000d, - OMX_ExtraDataInputBitsInfo = 0x7F00000e, - OMX_ExtraDataVideoEncoderMBInfo = 0x7F00000f, - OMX_ExtraDataVQZipSEI = 0x7F000010, -} OMX_QCOM_EXTRADATATYPE; - -typedef struct OMX_STREAMINTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bInterlaceFormat; - OMX_U32 nInterlaceFormats; -} OMX_STREAMINTERLACEFORMAT; - -typedef enum OMX_INTERLACETYPE -{ - OMX_InterlaceFrameProgressive, - OMX_InterlaceInterleaveFrameTopFieldFirst, - OMX_InterlaceInterleaveFrameBottomFieldFirst, - OMX_InterlaceFrameTopFieldFirst, - OMX_InterlaceFrameBottomFieldFirst -} OMX_INTERLACES; - - -#define OMX_EXTRADATA_HEADER_SIZE 20 - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum QOMX_VIDEO_AVCPROFILETYPE { - QOMX_VIDEO_AVCProfileBaseline = OMX_VIDEO_AVCProfileBaseline, - QOMX_VIDEO_AVCProfileMain = OMX_VIDEO_AVCProfileMain, - QOMX_VIDEO_AVCProfileExtended = OMX_VIDEO_AVCProfileExtended, - QOMX_VIDEO_AVCProfileHigh = OMX_VIDEO_AVCProfileHigh, - QOMX_VIDEO_AVCProfileHigh10 = OMX_VIDEO_AVCProfileHigh10, - QOMX_VIDEO_AVCProfileHigh422 = OMX_VIDEO_AVCProfileHigh422, - QOMX_VIDEO_AVCProfileHigh444 = OMX_VIDEO_AVCProfileHigh444, - /* QCom specific profile indexes */ - QOMX_VIDEO_AVCProfileConstrained = OMX_VIDEO_AVCProfileVendorStartUnused, - QOMX_VIDEO_AVCProfileConstrainedBaseline, - QOMX_VIDEO_AVCProfileConstrainedHigh, -} QOMX_VIDEO_AVCPROFILETYPE; - - -/** - * H.264 MVC Profiles - */ -typedef enum QOMX_VIDEO_MVCPROFILETYPE { - QOMX_VIDEO_MVCProfileStereoHigh = 0x1, - QOMX_VIDEO_MVCProfileMultiViewHigh = 0x2, - QOMX_VIDEO_MVCProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCPROFILETYPE; - -/** - * H.264 MVC Levels - */ -typedef enum QOMX_VIDEO_MVCLEVELTYPE { - QOMX_VIDEO_MVCLevel1 = 0x01, /**< Level 1 */ - QOMX_VIDEO_MVCLevel1b = 0x02, /**< Level 1b */ - QOMX_VIDEO_MVCLevel11 = 0x04, /**< Level 1.1 */ - QOMX_VIDEO_MVCLevel12 = 0x08, /**< Level 1.2 */ - QOMX_VIDEO_MVCLevel13 = 0x10, /**< Level 1.3 */ - QOMX_VIDEO_MVCLevel2 = 0x20, /**< Level 2 */ - QOMX_VIDEO_MVCLevel21 = 0x40, /**< Level 2.1 */ - QOMX_VIDEO_MVCLevel22 = 0x80, /**< Level 2.2 */ - QOMX_VIDEO_MVCLevel3 = 0x100, /**< Level 3 */ - QOMX_VIDEO_MVCLevel31 = 0x200, /**< Level 3.1 */ - QOMX_VIDEO_MVCLevel32 = 0x400, /**< Level 3.2 */ - QOMX_VIDEO_MVCLevel4 = 0x800, /**< Level 4 */ - QOMX_VIDEO_MVCLevel41 = 0x1000, /**< Level 4.1 */ - QOMX_VIDEO_MVCLevel42 = 0x2000, /**< Level 4.2 */ - QOMX_VIDEO_MVCLevel5 = 0x4000, /**< Level 5 */ - QOMX_VIDEO_MVCLevel51 = 0x8000, /**< Level 5.1 */ - QOMX_VIDEO_MVCLevelKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCLevelVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCLevelMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCLEVELTYPE; - -/** - * DivX Versions - */ -typedef enum QOMX_VIDEO_DIVXFORMATTYPE { - QOMX_VIDEO_DIVXFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_DIVXFormat311 = 0x02, /**< DivX 3.11 */ - QOMX_VIDEO_DIVXFormat4 = 0x04, /**< DivX 4 */ - QOMX_VIDEO_DIVXFormat5 = 0x08, /**< DivX 5 */ - QOMX_VIDEO_DIVXFormat6 = 0x10, /**< DivX 6 */ - QOMX_VIDEO_DIVXFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXFORMATTYPE; - -/** - * DivX profile types, each profile indicates support for - * various performance bounds. - */ -typedef enum QOMX_VIDEO_DIVXPROFILETYPE { - QOMX_VIDEO_DivXProfileqMobile = 0x01, /**< qMobile Profile */ - QOMX_VIDEO_DivXProfileMobile = 0x02, /**< Mobile Profile */ - QOMX_VIDEO_DivXProfileMT = 0x04, /**< Mobile Theatre Profile */ - QOMX_VIDEO_DivXProfileHT = 0x08, /**< Home Theatre Profile */ - QOMX_VIDEO_DivXProfileHD = 0x10, /**< High Definition Profile */ - QOMX_VIDEO_DIVXProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXPROFILETYPE; - -/** - * DivX Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of DivX stream / data - * eProfile : Profile of DivX stream / data - */ -typedef struct QOMX_VIDEO_PARAM_DIVXTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_DIVXFORMATTYPE eFormat; - QOMX_VIDEO_DIVXPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_DIVXTYPE; - - - -/** - * VP Versions - */ -typedef enum QOMX_VIDEO_VPFORMATTYPE { - QOMX_VIDEO_VPFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_VPFormat6 = 0x02, /**< VP6 Video Format */ - QOMX_VIDEO_VPFormat7 = 0x04, /**< VP7 Video Format */ - QOMX_VIDEO_VPFormat8 = 0x08, /**< VP8 Video Format */ - QOMX_VIDEO_VPFormat9 = 0x10, /**< VP9 Video Format */ - QOMX_VIDEO_VPFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_VPFORMATTYPE; - -/** - * VP profile types, each profile indicates support for various - * encoding tools. - */ -typedef enum QOMX_VIDEO_VPPROFILETYPE { - QOMX_VIDEO_VPProfileSimple = 0x01, /**< Simple Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileAdvanced = 0x02, /**< Advanced Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileVersion0 = 0x04, /**< Version 0, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion1 = 0x08, /**< Version 1, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion2 = 0x10, /**< Version 2, applies to VP8 only */ - QOMX_VIDEO_VPProfileVersion3 = 0x20, /**< Version 3, applies to VP8 only */ - QOMX_VIDEO_VPProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_VPPROFILETYPE; - -/** - * VP Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Format of VP stream / data - * eProfile : Profile or Version of VP stream / data - */ -typedef struct QOMX_VIDEO_PARAM_VPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_VPFORMATTYPE eFormat; - QOMX_VIDEO_VPPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_VPTYPE; - -/** - * Spark Versions - */ -typedef enum QOMX_VIDEO_SPARKFORMATTYPE { - QOMX_VIDEO_SparkFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_SparkFormat0 = 0x02, /**< Video Format Version 0 */ - QOMX_VIDEO_SparkFormat1 = 0x04, /**< Video Format Version 1 */ - QOMX_VIDEO_SparkFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_SparkFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_SparkFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_SPARKFORMATTYPE; - -/** - * Spark Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of Spark stream / data - */ -typedef struct QOMX_VIDEO_PARAM_SPARKTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_SPARKFORMATTYPE eFormat; -} QOMX_VIDEO_PARAM_SPARKTYPE; - - -typedef struct QOMX_VIDEO_QUERY_DECODER_INSTANCES { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumOfInstances; -} QOMX_VIDEO_QUERY_DECODER_INSTANCES; - -typedef struct QOMX_ENABLETYPE { - OMX_BOOL bEnable; -} QOMX_ENABLETYPE; - -typedef enum QOMX_VIDEO_EVENTS { - OMX_EventIndexsettingChanged = OMX_EventVendorStartUnused -} QOMX_VIDEO_EVENTS; - -typedef enum QOMX_VIDEO_PICTURE_ORDER { - QOMX_VIDEO_DISPLAY_ORDER = 0x1, - QOMX_VIDEO_DECODE_ORDER = 0x2 -} QOMX_VIDEO_PICTURE_ORDER; - -typedef struct QOMX_VIDEO_DECODER_PICTURE_ORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_PICTURE_ORDER eOutputPictureOrder; -} QOMX_VIDEO_DECODER_PICTURE_ORDER; - -typedef struct QOMX_INDEXEXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; - OMX_INDEXTYPE nIndex; -} QOMX_INDEXEXTRADATATYPE; - -typedef struct QOMX_INDEXTIMESTAMPREORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXTIMESTAMPREORDER; - -typedef struct QOMX_INDEXDOWNSCALAR { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXDOWNSCALAR; - -typedef struct QOMX_VIDEO_CUSTOM_BUFFERSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBufferSize; -} QOMX_VIDEO_CUSTOM_BUFFERSIZE; - -#define OMX_QCOM_INDEX_PARAM_VIDEO_SYNCFRAMEDECODINGMODE "OMX.QCOM.index.param.video.SyncFrameDecodingMode" -#define OMX_QCOM_INDEX_PARAM_INDEXEXTRADATA "OMX.QCOM.index.param.IndexExtraData" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SLICEDELIVERYMODE "OMX.QCOM.index.param.SliceDeliveryMode" -#define OMX_QCOM_INDEX_PARAM_VIDEO_FRAMEPACKING_EXTRADATA "OMX.QCOM.index.param.video.FramePackingExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_QP_EXTRADATA "OMX.QCOM.index.param.video.QPExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_INPUTBITSINFO_EXTRADATA "OMX.QCOM.index.param.video.InputBitsInfoExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_EXTNUSER_EXTRADATA "OMX.QCOM.index.param.video.ExtnUserExtraData" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_FRAMEPACKING_INFO "OMX.QCOM.index.config.video.FramePackingInfo" -#define OMX_QCOM_INDEX_PARAM_VIDEO_MPEG2SEQDISP_EXTRADATA "OMX.QCOM.index.param.video.Mpeg2SeqDispExtraData" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_HIERSTRUCTURE "OMX.QCOM.index.param.video.HierStructure" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRCOUNT "OMX.QCOM.index.param.video.LTRCount" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRPERIOD "OMX.QCOM.index.param.video.LTRPeriod" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE "OMX.QCOM.index.config.video.LTRUse" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRMARK "OMX.QCOM.index.config.video.LTRMark" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_HIER_P_LAYERS "OMX.QCOM.index.config.video.hierplayers" -#define OMX_QCOM_INDEX_CONFIG_RECTANGLE_TYPE "OMX.QCOM.index.config.video.rectangle" -#define OMX_QCOM_INDEX_PARAM_VIDEO_BASE_LAYER_ID "OMX.QCOM.index.param.video.baselayerid" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_QP "OMX.QCOM.index.config.video.qp" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SAR "OMX.QCOM.index.param.video.sar" -#define OMX_QTI_INDEX_PARAM_VIDEO_LOW_LATENCY "OMX.QTI.index.param.video.LowLatency" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_PASSINPUTBUFFERFD "OMX.QCOM.index.param.video.PassInputBufferFd" -#define OMX_QTI_INDEX_PARAM_VIDEO_PREFER_ADAPTIVE_PLAYBACK "OMX.QTI.index.param.video.PreferAdaptivePlayback" -#define OMX_QTI_INDEX_CONFIG_VIDEO_SETTIMEDATA "OMX.QTI.index.config.video.settimedata" -#define OMX_QTI_INDEX_PARAM_VIDEO_FORCE_COMPRESSED_FOR_DPB "OMX.QTI.index.param.video.ForceCompressedForDPB" -#define OMX_QTI_INDEX_PARAM_VIDEO_ENABLE_ROIINFO "OMX.QTI.index.param.enableRoiInfo" -#define OMX_QTI_INDEX_CONFIG_VIDEO_ROIINFO "OMX.QTI.index.config.RoiInfo" - -typedef enum { - QOMX_VIDEO_FRAME_PACKING_CHECKERBOARD = 0, - QOMX_VIDEO_FRAME_PACKING_COLUMN_INTERLEAVE = 1, - QOMX_VIDEO_FRAME_PACKING_ROW_INTERLEAVE = 2, - QOMX_VIDEO_FRAME_PACKING_SIDE_BY_SIDE = 3, - QOMX_VIDEO_FRAME_PACKING_TOP_BOTTOM = 4, - QOMX_VIDEO_FRAME_PACKING_TEMPORAL = 5, -} QOMX_VIDEO_FRAME_PACKING_ARRANGEMENT; - -typedef enum { - QOMX_VIDEO_CONTENT_UNSPECIFIED = 0, - QOMX_VIDEO_CONTENT_LR_VIEW = 1, - QOMX_VIDEO_CONTENT_RL_VIEW = 2, -} QOMX_VIDEO_CONTENT_INTERPRETATION; - -/** - * Specifies the extended picture types. These values should be - * OR'd along with the types defined in OMX_VIDEO_PICTURETYPE to - * signal all pictures types which are allowed. - * - * ENUMS: - * H.264 Specific Picture Types: IDR - */ -typedef enum QOMX_VIDEO_PICTURETYPE { - QOMX_VIDEO_PictureTypeIDR = OMX_VIDEO_PictureTypeVendorStartUnused + 0x1000 -} QOMX_VIDEO_PICTURETYPE; - -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION "OMX.QCOM.index.config.activeregiondetection" -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION_STATUS "OMX.QCOM.index.config.activeregiondetectionstatus" -#define OMX_QCOM_INDEX_CONFIG_SCALING_MODE "OMX.QCOM.index.config.scalingmode" -#define OMX_QCOM_INDEX_CONFIG_NOISEREDUCTION "OMX.QCOM.index.config.noisereduction" -#define OMX_QCOM_INDEX_CONFIG_IMAGEENHANCEMENT "OMX.QCOM.index.config.imageenhancement" -#define OMX_QCOM_INDEX_PARAM_HELDBUFFERCOUNT "OMX.QCOM.index.param.HeldBufferCount" /**< reference: QOMX_HELDBUFFERCOUNTTYPE */ - - -typedef struct QOMX_RECTTYPE { - OMX_S32 nLeft; - OMX_S32 nTop; - OMX_U32 nWidth; - OMX_U32 nHeight; -} QOMX_RECTTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - QOMX_RECTTYPE sROI; - OMX_U32 nNumExclusionRegions; - QOMX_RECTTYPE sExclusionRegions[1]; -} QOMX_ACTIVEREGIONDETECTIONTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTION_STATUSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bDetected; - QOMX_RECTTYPE sDetectedRegion; -} QOMX_ACTIVEREGIONDETECTION_STATUSTYPE; - -typedef enum QOMX_SCALE_MODETYPE { - QOMX_SCALE_MODE_Normal, - QOMX_SCALE_MODE_Anamorphic, - QOMX_SCALE_MODE_Max = 0x7FFFFFFF -} QOMX_SCALE_MODETYPE; - -typedef struct QOMX_SCALINGMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - QOMX_SCALE_MODETYPE eScaleMode; -} QOMX_SCALINGMODETYPE; - -typedef struct QOMX_NOISEREDUCTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nNoiseReduction; -} QOMX_NOISEREDUCTIONTYPE; - -typedef struct QOMX_IMAGEENHANCEMENTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nImageEnhancement; -} QOMX_IMAGEENHANCEMENTTYPE; - -/* - * these are part of OMX1.2 but JB MR2 branch doesn't have them defined - * OMX_IndexParamInterlaceFormat - * OMX_INTERLACEFORMATTYPE - */ -#ifndef OMX_IndexParamInterlaceFormat -#define OMX_IndexParamInterlaceFormat (0x7FF00000) -typedef struct OMX_INTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFormat; - OMX_TICKS nTimeStamp; -} OMX_INTERLACEFORMATTYPE; -#endif - -/** - * This structure is used to indicate the maximum number of buffers - * that a port will hold during data flow. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nHeldBufferCount : Read-only, maximum number of buffers that will be held - */ -typedef struct QOMX_HELDBUFFERCOUNTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nHeldBufferCount; -} QOMX_HELDBUFFERCOUNTTYPE; - -typedef enum QOMX_VIDEO_HIERARCHICALCODINGTYPE { - QOMX_HIERARCHICALCODING_P = 0x01, - QOMX_HIERARCHICALCODING_B = 0x02, -} QOMX_VIDEO_HIERARCHICALCODINGTYPE; - -typedef struct QOMX_VIDEO_HIERARCHICALLAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumLayers; - QOMX_VIDEO_HIERARCHICALCODINGTYPE eHierarchicalCodingType; -} QOMX_VIDEO_HIERARCHICALLAYERS; - -typedef struct QOMX_VIDEO_H264ENTROPYCODINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bCabac; - OMX_U32 nCabacInitIdc; -} QOMX_VIDEO_H264ENTROPYCODINGTYPE; - - -/* VIDEO POSTPROCESSING CTRLS AND ENUMS */ -#define QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ 256 -#define VPP_HQV_CONTROL_GLOBAL_START (VPP_HQV_CONTROL_CUST + 1) - -typedef enum QOMX_VPP_HQV_MODE { - VPP_HQV_MODE_OFF, - VPP_HQV_MODE_AUTO, - VPP_HQV_MODE_MANUAL, - VPP_HQV_MODE_MAX -} QOMX_VPP_HQV_MODE; - -typedef enum QOMX_VPP_HQVCONTROLTYPE { - VPP_HQV_CONTROL_CADE = 0x1, - VPP_HQV_CONTROL_CNR = 0x04, - VPP_HQV_CONTROL_AIE = 0x05, - VPP_HQV_CONTROL_FRC = 0x06, - VPP_HQV_CONTROL_CUST = 0x07, - VPP_HQV_CONTROL_GLOBAL_DEMO = VPP_HQV_CONTROL_GLOBAL_START, - VPP_HQV_CONTROL_MAX, -} QOMX_VPP_HQVCONTROLTYPE; - -typedef enum QOMX_VPP_HQV_HUE_MODE { - VPP_HQV_HUE_MODE_OFF, - VPP_HQV_HUE_MODE_ON, - VPP_HQV_HUE_MODE_MAX, -} QOMX_VPP_HQV_HUE_MODE; - -typedef enum QOMX_VPP_HQV_FRC_MODE { - VPP_HQV_FRC_MODE_OFF, - VPP_HQV_FRC_MODE_LOW, - VPP_HQV_FRC_MODE_MED, - VPP_HQV_FRC_MODE_HIGH, - VPP_HQV_FRC_MODE_MAX, -} QOMX_VPP_HQV_FRC_MODE; - - -typedef struct QOMX_VPP_HQVCTRL_CADE { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; - OMX_S32 contrast; - OMX_S32 saturation; -} QOMX_VPP_HQVCTRL_CADE; - -typedef struct QOMX_VPP_HQVCTRL_CNR { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; -} QOMX_VPP_HQVCTRL_CNR; - -typedef struct QOMX_VPP_HQVCTRL_AIE { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQV_HUE_MODE hue_mode; - OMX_U32 cade_level; - OMX_U32 ltm_level; -} QOMX_VPP_HQVCTRL_AIE; - -typedef struct QOMX_VPP_HQVCTRL_CUSTOM { - OMX_U32 id; - OMX_U32 len; - OMX_U8 data[QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ]; -} QOMX_VPP_HQVCTRL_CUSTOM; - -typedef struct QOMX_VPP_HQVCTRL_GLOBAL_DEMO { - OMX_U32 process_percent; -} QOMX_VPP_HQVCTRL_GLOBAL_DEMO; - -typedef struct QOMX_VPP_HQVCTRL_FRC { - QOMX_VPP_HQV_FRC_MODE mode; -} QOMX_VPP_HQVCTRL_FRC; - -typedef struct QOMX_VPP_HQVCONTROL { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQVCONTROLTYPE ctrl_type; - union { - QOMX_VPP_HQVCTRL_CADE cade; - QOMX_VPP_HQVCTRL_CNR cnr; - QOMX_VPP_HQVCTRL_AIE aie; - QOMX_VPP_HQVCTRL_CUSTOM custom; - QOMX_VPP_HQVCTRL_GLOBAL_DEMO global_demo; - QOMX_VPP_HQVCTRL_FRC frc; - }; -} QOMX_VPP_HQVCONTROL; - -/* STRUCTURE TO TURN VPP ON */ -typedef struct QOMX_VPP_ENABLE { - OMX_BOOL enable_vpp; -} QOMX_VPP_ENABLE; - -typedef enum OMX_QOMX_VIDEO_MBISTATISTICSTYPE { - QOMX_MBI_STATISTICS_MODE_DEFAULT = 0, - QOMX_MBI_STATISTICS_MODE_1 = 0x01, - QOMX_MBI_STATISTICS_MODE_2 = 0x02, -} OMX_QOMX_VIDEO_MBISTATISTICSTYPE; - -typedef struct OMX_QOMX_VIDEO_MBI_STATISTICS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_QOMX_VIDEO_MBISTATISTICSTYPE eMBIStatisticsType; -} OMX_QOMX_VIDEO_MBI_STATISTICS; - -typedef struct QOMX_VIDEO_BATCHSIZETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBatchSize; -} QOMX_VIDEO_BATCHSIZETYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __OMX_QCOM_EXTENSIONS_H__ */ diff --git a/third_party/openmax/include/OMX_Skype_VideoExtensions.h b/third_party/openmax/include/OMX_Skype_VideoExtensions.h deleted file mode 100644 index 5cc832930f..0000000000 --- a/third_party/openmax/include/OMX_Skype_VideoExtensions.h +++ /dev/null @@ -1,155 +0,0 @@ -/*@@@+++@@@@****************************************************************** - - Microsoft Skype Engineering - Copyright (C) 2014 Microsoft Corporation. - -MIT License - -Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - -*@@@---@@@@******************************************************************/ - - -#ifndef __OMX_SKYPE_VIDEOEXTENSIONS_H__ -#define __OMX_SKYPE_VIDEOEXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" -{ -#endif - -#include - -#pragma pack(push, 1) - - -typedef enum OMX_SKYPE_VIDEO_SliceControlMode -{ - OMX_SKYPE_VIDEO_SliceControlModeNone = 0, - OMX_SKYPE_VIDEO_SliceControlModeMB = 1, - OMX_SKYPE_VIDEO_SliceControlModeByte = 2, - OMX_SKYPE_VIDEO_SliceControlModMBRow = 3, -} OMX_SKYPE_VIDEO_SliceControlMode; - - -typedef enum OMX_SKYPE_VIDEO_HierarType -{ - OMX_SKYPE_VIDEO_HierarType_P = 0x01, - OMX_SKYPE_VIDEO_HierarType_B = 0x02, -} OMX_SKYPE_VIDEO_HIERAR_HierarType; - -typedef enum OMX_VIDEO_EXTENSION_AVCPROFILETYPE -{ - OMX_VIDEO_EXT_AVCProfileConstrainedBaseline = 0x01, - OMX_VIDEO_EXT_AVCProfileConstrainedHigh = 0x02, -} OMX_VIDEO_EXTENSION_AVCPROFILETYPE; - -typedef struct OMX_SKYPE_VIDEO_ENCODERPARAMS { - OMX_BOOL bLowLatency; - OMX_BOOL bUseExtendedProfile; - OMX_BOOL bSequenceHeaderWithIDR; - OMX_VIDEO_EXTENSION_AVCPROFILETYPE eProfile; - OMX_U32 nLTRFrames; - OMX_SKYPE_VIDEO_HierarType eHierarType; - OMX_U32 nMaxTemporalLayerCount; - OMX_SKYPE_VIDEO_SliceControlMode eSliceControlMode; - OMX_U32 nSarIndex; - OMX_U32 nSarWidth; - OMX_U32 nSarHeight; -} OMX_SKYPE_VIDEO_ENCODERPARAMS; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERSETTING { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERPARAMS stEncParam; -} OMX_SKYPE_VIDEO_PARAM_ENCODESETTING; - -typedef struct OMX_SKYPE_VIDEO_ENCODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_U32 nMaxTemporaLayerCount; - OMX_U32 nMaxRefFrames; - OMX_U32 nMaxLTRFrames; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nSliceControlModesBM; - OMX_U32 nMaxMacroblockProcessingRate; - OMX_U32 xMinScaleFactor; -} OMX_SKYPE_VIDEO_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERCAP stEncCap; -} OMX_SKYPE_VIDEO_PARAM_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_DECODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nMaxMacroblockProcessingRate; -} OMX_SKYPE_VIDEO_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DECODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_DECODERCAP stDecoderCap; -} OMX_SKYPE_VIDEO_PARAM_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_QP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQP; -} OMX_SKYPE_VIDEO_CONFIG_QP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPID; -} OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DRIVERVER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U64 nDriverVersion; -} OMX_SKYPE_VIDEO_PARAM_DRIVERVER; - -typedef enum OMX_SKYPE_VIDEO_DownScaleFactor -{ - OMX_SKYPE_VIDEO_DownScaleFactor_1_1 = 0, - OMX_SKYPE_VIDEO_DownScaleFactor_Equal_AR = 1, - OMX_SKYPE_VIDEO_DownScaleFactor_Any = 2, -} OMX_SKYPE_VIDEO_DownScaleFactor; - -#pragma pack(pop) - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/third_party/openmax/include/OMX_Types.h b/third_party/openmax/include/OMX_Types.h deleted file mode 100644 index 3b9fab4fc2..0000000000 --- a/third_party/openmax/include/OMX_Types.h +++ /dev/null @@ -1,359 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Types.h - OpenMax IL version 1.1.2 - * The OMX_Types header file contains the primitive type definitions used by - * the core, the application and the component. This file may need to be - * modified to be used on systems that do not have "char" set to 8 bits, - * "short" set to 16 bits and "long" set to 32 bits. - */ - -#ifndef OMX_Types_h -#define OMX_Types_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** The OMX_API and OMX_APIENTRY are platform specific definitions used - * to declare OMX function prototypes. They are modified to meet the - * requirements for a particular platform */ -#ifdef __SYMBIAN32__ -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# ifdef _WIN32 -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# endif -#else -# ifdef _WIN32 -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# else -# ifdef __OMX_EXPORTS -# define OMX_API -# else -# define OMX_API extern -# endif -# endif -#endif - -#ifndef OMX_APIENTRY -#define OMX_APIENTRY -#endif - -/** OMX_IN is used to identify inputs to an OMX function. This designation - will also be used in the case of a pointer that points to a parameter - that is used as an output. */ -#ifndef OMX_IN -#define OMX_IN -#endif - -/** OMX_OUT is used to identify outputs from an OMX function. This - designation will also be used in the case of a pointer that points - to a parameter that is used as an input. */ -#ifndef OMX_OUT -#define OMX_OUT -#endif - - -/** OMX_INOUT is used to identify parameters that may be either inputs or - outputs from an OMX function at the same time. This designation will - also be used in the case of a pointer that points to a parameter that - is used both as an input and an output. */ -#ifndef OMX_INOUT -#define OMX_INOUT -#endif - -/** OMX_ALL is used to as a wildcard to select all entities of the same type - * when specifying the index, or referring to a object by an index. (i.e. - * use OMX_ALL to indicate all N channels). When used as a port index - * for a config or parameter this OMX_ALL denotes that the config or - * parameter applies to the entire component not just one port. */ -#define OMX_ALL 0xFFFFFFFF - -/** In the following we define groups that help building doxygen documentation */ - -/** @defgroup core OpenMAX IL core - * Functions and structure related to the OMX IL core - */ - - /** @defgroup comp OpenMAX IL component - * Functions and structure related to the OMX IL component - */ - -/** @defgroup rpm Resource and Policy Management - * Structures for resource and policy management of components - */ - -/** @defgroup buf Buffer Management - * Buffer handling functions and structures - */ - -/** @defgroup tun Tunneling - * @ingroup core comp - * Structures and functions to manage tunnels among component ports - */ - -/** @defgroup cp Content Pipes - * @ingroup core - */ - - /** @defgroup metadata Metadata handling - * - */ - -/** OMX_U8 is an 8 bit unsigned quantity that is byte aligned */ -typedef unsigned char OMX_U8; - -/** OMX_S8 is an 8 bit signed quantity that is byte aligned */ -typedef signed char OMX_S8; - -/** OMX_U16 is a 16 bit unsigned quantity that is 16 bit word aligned */ -typedef unsigned short OMX_U16; - -/** OMX_S16 is a 16 bit signed quantity that is 16 bit word aligned */ -typedef signed short OMX_S16; - -/** OMX_U32 is a 32 bit unsigned quantity that is 32 bit word aligned */ -typedef unsigned int OMX_U32; - -/** OMX_S32 is a 32 bit signed quantity that is 32 bit word aligned */ -typedef signed int OMX_S32; - - -/* Users with compilers that cannot accept the "long long" designation should - define the OMX_SKIP64BIT macro. It should be noted that this may cause - some components to fail to compile if the component was written to require - 64 bit integral types. However, these components would NOT compile anyway - since the compiler does not support the way the component was written. -*/ -#ifndef OMX_SKIP64BIT -#ifdef __SYMBIAN32__ -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#elif defined(WIN32) - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned __int64 OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed __int64 OMX_S64; - -#else /* WIN32 */ - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#endif /* WIN32 */ -#endif - - -/** The OMX_BOOL type is intended to be used to represent a true or a false - value when passing parameters to and from the OMX core and components. The - OMX_BOOL is a 32 bit quantity and is aligned on a 32 bit word boundary. - */ -typedef enum OMX_BOOL { - OMX_FALSE = 0, - OMX_TRUE = !OMX_FALSE, - OMX_BOOL_MAX = 0x7FFFFFFF -} OMX_BOOL; - -#ifdef OMX_ANDROID_COMPILE_AS_32BIT_ON_64BIT_PLATFORMS - -typedef OMX_U32 OMX_PTR; -typedef OMX_PTR OMX_STRING; -typedef OMX_PTR OMX_BYTE; - -#else - -/** The OMX_PTR type is intended to be used to pass pointers between the OMX - applications and the OMX Core and components. This is a 32 bit pointer and - is aligned on a 32 bit boundary. - */ -typedef void* OMX_PTR; - -/** The OMX_STRING type is intended to be used to pass "C" type strings between - the application and the core and component. The OMX_STRING type is a 32 - bit pointer to a zero terminated string. The pointer is word aligned and - the string is byte aligned. - */ -typedef char* OMX_STRING; - -/** The OMX_BYTE type is intended to be used to pass arrays of bytes such as - buffers between the application and the component and core. The OMX_BYTE - type is a 32 bit pointer to a zero terminated string. The pointer is word - aligned and the string is byte aligned. - */ -typedef unsigned char* OMX_BYTE; - -/** OMX_UUIDTYPE is a very long unique identifier to uniquely identify - at runtime. This identifier should be generated by a component in a way - that guarantees that every instance of the identifier running on the system - is unique. */ - - -#endif - -typedef unsigned char OMX_UUIDTYPE[128]; - -/** The OMX_DIRTYPE enumeration is used to indicate if a port is an input or - an output port. This enumeration is common across all component types. - */ -typedef enum OMX_DIRTYPE -{ - OMX_DirInput, /**< Port is an input port */ - OMX_DirOutput, /**< Port is an output port */ - OMX_DirMax = 0x7FFFFFFF -} OMX_DIRTYPE; - -/** The OMX_ENDIANTYPE enumeration is used to indicate the bit ordering - for numerical data (i.e. big endian, or little endian). - */ -typedef enum OMX_ENDIANTYPE -{ - OMX_EndianBig, /**< big endian */ - OMX_EndianLittle, /**< little endian */ - OMX_EndianMax = 0x7FFFFFFF -} OMX_ENDIANTYPE; - - -/** The OMX_NUMERICALDATATYPE enumeration is used to indicate if data - is signed or unsigned - */ -typedef enum OMX_NUMERICALDATATYPE -{ - OMX_NumericalDataSigned, /**< signed data */ - OMX_NumericalDataUnsigned, /**< unsigned data */ - OMX_NumercialDataMax = 0x7FFFFFFF -} OMX_NUMERICALDATATYPE; - - -/** Unsigned bounded value type */ -typedef struct OMX_BU32 { - OMX_U32 nValue; /**< actual value */ - OMX_U32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_U32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BU32; - - -/** Signed bounded value type */ -typedef struct OMX_BS32 { - OMX_S32 nValue; /**< actual value */ - OMX_S32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_S32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BS32; - - -/** Structure representing some time or duration in microseconds. This structure - * must be interpreted as a signed 64 bit value. The quantity is signed to accommodate - * negative deltas and preroll scenarios. The quantity is represented in microseconds - * to accomodate high resolution timestamps (e.g. DVD presentation timestamps based - * on a 90kHz clock) and to allow more accurate and synchronized delivery (e.g. - * individual audio samples delivered at 192 kHz). The quantity is 64 bit to - * accommodate a large dynamic range (signed 32 bit values would allow only for plus - * or minus 35 minutes). - * - * Implementations with limited precision may convert the signed 64 bit value to - * a signed 32 bit value internally but risk loss of precision. - */ -#ifndef OMX_SKIP64BIT -typedef OMX_S64 OMX_TICKS; -#else -typedef struct OMX_TICKS -{ - OMX_U32 nLowPart; /** low bits of the signed 64 bit tick value */ - OMX_U32 nHighPart; /** high bits of the signed 64 bit tick value */ -} OMX_TICKS; -#endif -#define OMX_TICKS_PER_SECOND 1000000 - -/** Define the public interface for the OMX Handle. The core will not use - this value internally, but the application should only use this value. - */ -typedef void* OMX_HANDLETYPE; - -typedef struct OMX_MARKTYPE -{ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will - generate a mark event upon - processing the mark. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ -} OMX_MARKTYPE; - - -/** OMX_NATIVE_DEVICETYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the display - * or can be used by a audio port for native audio rendering */ -typedef void* OMX_NATIVE_DEVICETYPE; - -/** OMX_NATIVE_WINDOWTYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the window */ -typedef void* OMX_NATIVE_WINDOWTYPE; - -/** The OMX_VERSIONTYPE union is used to specify the version for - a structure or component. For a component, the version is entirely - specified by the component vendor. Components doing the same function - from different vendors may or may not have the same version. For - structures, the version shall be set by the entity that allocates the - structure. For structures specified in the OMX 1.1 specification, the - value of the version shall be set to 1.1.0.0 in all cases. Access to the - OMX_VERSIONTYPE can be by a single 32 bit access (e.g. by nVersion) or - by accessing one of the structure elements to, for example, check only - the Major revision. - */ -typedef union OMX_VERSIONTYPE -{ - struct - { - OMX_U8 nVersionMajor; /**< Major version accessor element */ - OMX_U8 nVersionMinor; /**< Minor version accessor element */ - OMX_U8 nRevision; /**< Revision version accessor element */ - OMX_U8 nStep; /**< Step version accessor element */ - } s; - OMX_U32 nVersion; /**< 32 bit value to make accessing the - version easily done in a single word - size copy/compare operation */ -} OMX_VERSIONTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Video.h b/third_party/openmax/include/OMX_Video.h deleted file mode 100644 index 64dbe87b43..0000000000 --- a/third_party/openmax/include/OMX_Video.h +++ /dev/null @@ -1,1082 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_Video.h - OpenMax IL version 1.1.2 - * The structures is needed by Video components to exchange parameters - * and configuration data with OMX components. - */ -#ifndef OMX_Video_h -#define OMX_Video_h - -/** @defgroup video OpenMAX IL Video Domain - * @ingroup iv - * Structures for OpenMAX IL Video domain - * @{ - */ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/** - * Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration used to define the possible video compression codings. - * NOTE: This essentially refers to file extensions. If the coding is - * being used to specify the ENCODE type, then additional work - * must be done to configure the exact flavor of the compression - * to be used. For decode cases where the user application can - * not differentiate between MPEG-4 and H.264 bit streams, it is - * up to the codec to handle this. - */ -typedef enum OMX_VIDEO_CODINGTYPE { - OMX_VIDEO_CodingUnused, /**< Value when coding is N/A */ - OMX_VIDEO_CodingAutoDetect, /**< Autodetection of coding type */ - OMX_VIDEO_CodingMPEG2, /**< AKA: H.262 */ - OMX_VIDEO_CodingH263, /**< H.263 */ - OMX_VIDEO_CodingMPEG4, /**< MPEG-4 */ - OMX_VIDEO_CodingWMV, /**< all versions of Windows Media Video */ - OMX_VIDEO_CodingRV, /**< all versions of Real Video */ - OMX_VIDEO_CodingAVC, /**< H.264/AVC */ - OMX_VIDEO_CodingMJPEG, /**< Motion JPEG */ - OMX_VIDEO_CodingVP8, /**< Google VP8, formerly known as On2 VP8 */ - OMX_VIDEO_CodingVP9, /**< Google VP9 */ - OMX_VIDEO_CodingHEVC, /**< HEVC */ - OMX_VIDEO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_CodingMax = 0x7FFFFFFF -} OMX_VIDEO_CODINGTYPE; - - -/** - * Data structure used to define a video path. The number of Video paths for - * input and output will vary by type of the Video component. - * - * Input (aka Source) : zero Inputs, one Output, - * Splitter : one Input, 2 or more Outputs, - * Processing Element : one Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : one Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output video - * path. If additional vendor specific data is required, it should be - * transmitted to the component using the CustomCommand function. Compliant - * components will prepopulate this structure with optimal values during the - * GetDefaultInitParams command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nFrameHeight : Height of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nStride : Number of bytes per span of an image - * (i.e. indicates the number of bytes to get - * from span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * nBitrate : Bit rate of frame to be used on channel if - * compressed format is used. Use 0 for unknown, - * don't care or variable - * xFramerate : Frame rate to be used on channel if uncompressed - * format is used. Use 0 for unknown, don't care or - * variable. Units are Q16 frames per second. - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is - * specified, eColorFormat is used - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_VIDEO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_U32 nBitrate; - OMX_U32 xFramerate; - OMX_BOOL bFlagErrorConcealment; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_VIDEO_PORTDEFINITIONTYPE; - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is specified, - * eColorFormat is used - * eColorFormat : Decompressed format used by this component - * xFrameRate : Indicates the video frame rate in Q16 format - */ -typedef struct OMX_VIDEO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_U32 xFramerate; -} OMX_VIDEO_PARAM_PORTFORMATTYPE; - - -/** - * This is a structure for configuring video compression quantization - * parameter values. Codecs may support different QP values for different - * frame types. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nQpI : QP value to use for index frames - * nQpP : QP value to use for P frames - * nQpB : QP values to use for bidirectional frames - */ -typedef struct OMX_VIDEO_PARAM_QUANTIZATIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; -} OMX_VIDEO_PARAM_QUANTIZATIONTYPE; - - -/** - * Structure for configuration of video fast update parameters. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * bEnableVFU : Enable/Disable video fast update - * nFirstGOB : Specifies the number of the first macroblock row - * nFirstMB : specifies the first MB relative to the specified first GOB - * nNumMBs : Specifies the number of MBs to be refreshed from nFirstGOB - * and nFirstMB - */ -typedef struct OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableVFU; - OMX_U32 nFirstGOB; - OMX_U32 nFirstMB; - OMX_U32 nNumMBs; -} OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE; - - -/** - * Enumeration of possible bitrate control types - */ -typedef enum OMX_VIDEO_CONTROLRATETYPE { - OMX_Video_ControlRateDisable, - OMX_Video_ControlRateVariable, - OMX_Video_ControlRateConstant, - OMX_Video_ControlRateVariableSkipFrames, - OMX_Video_ControlRateConstantSkipFrames, - OMX_Video_ControlRateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_ControlRateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_ControlRateMax = 0x7FFFFFFF -} OMX_VIDEO_CONTROLRATETYPE; - - -/** - * Structure for configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * eControlRate : Control rate type enum - * nTargetBitrate : Target bitrate to encode with - */ -typedef struct OMX_VIDEO_PARAM_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_CONTROLRATETYPE eControlRate; - OMX_U32 nTargetBitrate; -} OMX_VIDEO_PARAM_BITRATETYPE; - - -/** - * Enumeration of possible motion vector (MV) types - */ -typedef enum OMX_VIDEO_MOTIONVECTORTYPE { - OMX_Video_MotionVectorPixel, - OMX_Video_MotionVectorHalfPel, - OMX_Video_MotionVectorQuarterPel, - OMX_Video_MotionVectorEighthPel, - OMX_Video_MotionVectorKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_MotionVectorVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_MotionVectorMax = 0x7FFFFFFF -} OMX_VIDEO_MOTIONVECTORTYPE; - - -/** - * Structure for configuring the number of motion vectors used as well - * as their accuracy. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : port that this structure applies to - * eAccuracy : Enumerated MV accuracy - * bUnrestrictedMVs : Allow unrestricted MVs - * bFourMV : Allow use of 4 MVs - * sXSearchRange : Search range in horizontal direction for MVs - * sYSearchRange : Search range in vertical direction for MVs - */ -typedef struct OMX_VIDEO_PARAM_MOTIONVECTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_MOTIONVECTORTYPE eAccuracy; - OMX_BOOL bUnrestrictedMVs; - OMX_BOOL bFourMV; - OMX_S32 sXSearchRange; - OMX_S32 sYSearchRange; -} OMX_VIDEO_PARAM_MOTIONVECTORTYPE; - - -/** - * Enumeration of possible methods to use for Intra Refresh - */ -typedef enum OMX_VIDEO_INTRAREFRESHTYPE { - OMX_VIDEO_IntraRefreshCyclic, - OMX_VIDEO_IntraRefreshAdaptive, - OMX_VIDEO_IntraRefreshBoth, - OMX_VIDEO_IntraRefreshKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_IntraRefreshVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_IntraRefreshRandom, - OMX_VIDEO_IntraRefreshMax = 0x7FFFFFFF -} OMX_VIDEO_INTRAREFRESHTYPE; - - -/** - * Structure for configuring intra refresh mode - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eRefreshMode : Cyclic, Adaptive, or Both - * nAirMBs : Number of intra macroblocks to refresh in a frame when - * AIR is enabled - * nAirRef : Number of times a motion marked macroblock has to be - * intra coded - * nCirMBs : Number of consecutive macroblocks to be coded as "intra" - * when CIR is enabled - */ -typedef struct OMX_VIDEO_PARAM_INTRAREFRESHTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_INTRAREFRESHTYPE eRefreshMode; - OMX_U32 nAirMBs; - OMX_U32 nAirRef; - OMX_U32 nCirMBs; -} OMX_VIDEO_PARAM_INTRAREFRESHTYPE; - - -/** - * Structure for enabling various error correction methods for video - * compression. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * bEnableHEC : Enable/disable header extension codes (HEC) - * bEnableResync : Enable/disable resynchronization markers - * nResynchMarkerSpacing : Resynch markers interval (in bits) to be - * applied in the stream - * bEnableDataPartitioning : Enable/disable data partitioning - * bEnableRVLC : Enable/disable reversible variable length - * coding - */ -typedef struct OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableHEC; - OMX_BOOL bEnableResync; - OMX_U32 nResynchMarkerSpacing; - OMX_BOOL bEnableDataPartitioning; - OMX_BOOL bEnableRVLC; -} OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE; - - -/** - * Configuration of variable block-size motion compensation (VBSMC) - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * b16x16 : Enable inter block search 16x16 - * b16x8 : Enable inter block search 16x8 - * b8x16 : Enable inter block search 8x16 - * b8x8 : Enable inter block search 8x8 - * b8x4 : Enable inter block search 8x4 - * b4x8 : Enable inter block search 4x8 - * b4x4 : Enable inter block search 4x4 - */ -typedef struct OMX_VIDEO_PARAM_VBSMCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL b16x16; - OMX_BOOL b16x8; - OMX_BOOL b8x16; - OMX_BOOL b8x8; - OMX_BOOL b8x4; - OMX_BOOL b4x8; - OMX_BOOL b4x4; -} OMX_VIDEO_PARAM_VBSMCTYPE; - - -/** - * H.263 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * Baseline : Baseline Profile: H.263 (V1), no optional modes - * H320 Coding : H.320 Coding Efficiency Backward Compatibility - * Profile: H.263+ (V2), includes annexes I, J, L.4 - * and T - * BackwardCompatible : Backward Compatibility Profile: H.263 (V1), - * includes annex F - * ISWV2 : Interactive Streaming Wireless Profile: H.263+ - * (V2), includes annexes I, J, K and T - * ISWV3 : Interactive Streaming Wireless Profile: H.263++ - * (V3), includes profile 3 and annexes V and W.6.3.8 - * HighCompression : Conversational High Compression Profile: H.263++ - * (V3), includes profiles 1 & 2 and annexes D and U - * Internet : Conversational Internet Profile: H.263++ (V3), - * includes profile 5 and annex K - * Interlace : Conversational Interlace Profile: H.263++ (V3), - * includes profile 5 and annex W.6.3.11 - * HighLatency : High Latency Profile: H.263++ (V3), includes - * profile 6 and annexes O.1 and P.5 - */ -typedef enum OMX_VIDEO_H263PROFILETYPE { - OMX_VIDEO_H263ProfileBaseline = 0x01, - OMX_VIDEO_H263ProfileH320Coding = 0x02, - OMX_VIDEO_H263ProfileBackwardCompatible = 0x04, - OMX_VIDEO_H263ProfileISWV2 = 0x08, - OMX_VIDEO_H263ProfileISWV3 = 0x10, - OMX_VIDEO_H263ProfileHighCompression = 0x20, - OMX_VIDEO_H263ProfileInternet = 0x40, - OMX_VIDEO_H263ProfileInterlace = 0x80, - OMX_VIDEO_H263ProfileHighLatency = 0x100, - OMX_VIDEO_H263ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_H263PROFILETYPE; - - -/** - * H.263 level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. - */ -typedef enum OMX_VIDEO_H263LEVELTYPE { - OMX_VIDEO_H263Level10 = 0x01, - OMX_VIDEO_H263Level20 = 0x02, - OMX_VIDEO_H263Level30 = 0x04, - OMX_VIDEO_H263Level40 = 0x08, - OMX_VIDEO_H263Level45 = 0x10, - OMX_VIDEO_H263Level50 = 0x20, - OMX_VIDEO_H263Level60 = 0x40, - OMX_VIDEO_H263Level70 = 0x80, - OMX_VIDEO_H263LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263LevelMax = 0x7FFFFFFF -} OMX_VIDEO_H263LEVELTYPE; - - -/** - * Specifies the picture type. These values should be OR'd to signal all - * pictures types which are allowed. - * - * ENUMS: - * Generic Picture Types: I, P and B - * H.263 Specific Picture Types: SI and SP - * H.264 Specific Picture Types: EI and EP - * MPEG-4 Specific Picture Types: S - */ -typedef enum OMX_VIDEO_PICTURETYPE { - OMX_VIDEO_PictureTypeI = 0x01, - OMX_VIDEO_PictureTypeP = 0x02, - OMX_VIDEO_PictureTypeB = 0x04, - OMX_VIDEO_PictureTypeSI = 0x08, - OMX_VIDEO_PictureTypeSP = 0x10, - OMX_VIDEO_PictureTypeEI = 0x11, - OMX_VIDEO_PictureTypeEP = 0x12, - OMX_VIDEO_PictureTypeS = 0x14, - OMX_VIDEO_PictureTypeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_PictureTypeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_PictureTypeMax = 0x7FFFFFFF -} OMX_VIDEO_PICTURETYPE; - - -/** - * H.263 Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : H.263 profile(s) to use - * eLevel : H.263 level(s) to use - * bPLUSPTYPEAllowed : Indicating that it is allowed to use PLUSPTYPE - * (specified in the 1998 version of H.263) to - * indicate custom picture sizes or clock - * frequencies - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bForceRoundingTypeToZero : value of the RTYPE bit (bit 6 of MPPTYPE) is - * not constrained. It is recommended to change - * the value of the RTYPE bit for each reference - * picture in error-free communication - * nPictureHeaderRepetition : Specifies the frequency of picture header - * repetition - * nGOBHeaderInterval : Specifies the interval of non-empty GOB - * headers in units of GOBs - */ -typedef struct OMX_VIDEO_PARAM_H263TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_H263PROFILETYPE eProfile; - OMX_VIDEO_H263LEVELTYPE eLevel; - OMX_BOOL bPLUSPTYPEAllowed; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bForceRoundingTypeToZero; - OMX_U32 nPictureHeaderRepetition; - OMX_U32 nGOBHeaderInterval; -} OMX_VIDEO_PARAM_H263TYPE; - - -/** - * MPEG-2 profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_MPEG2PROFILETYPE { - OMX_VIDEO_MPEG2ProfileSimple = 0, /**< Simple Profile */ - OMX_VIDEO_MPEG2ProfileMain, /**< Main Profile */ - OMX_VIDEO_MPEG2Profile422, /**< 4:2:2 Profile */ - OMX_VIDEO_MPEG2ProfileSNR, /**< SNR Profile */ - OMX_VIDEO_MPEG2ProfileSpatial, /**< Spatial Profile */ - OMX_VIDEO_MPEG2ProfileHigh, /**< High Profile */ - OMX_VIDEO_MPEG2ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2PROFILETYPE; - - -/** - * MPEG-2 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG2LEVELTYPE { - OMX_VIDEO_MPEG2LevelLL = 0, /**< Low Level */ - OMX_VIDEO_MPEG2LevelML, /**< Main Level */ - OMX_VIDEO_MPEG2LevelH14, /**< High 1440 */ - OMX_VIDEO_MPEG2LevelHL, /**< High Level */ - OMX_VIDEO_MPEG2LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2LEVELTYPE; - - -/** - * MPEG-2 params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : MPEG-2 profile(s) to use - * eLevel : MPEG-2 levels(s) to use - */ -typedef struct OMX_VIDEO_PARAM_MPEG2TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_MPEG2PROFILETYPE eProfile; - OMX_VIDEO_MPEG2LEVELTYPE eLevel; -} OMX_VIDEO_PARAM_MPEG2TYPE; - - -/** - * MPEG-4 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * - Simple Profile, Levels 1-3 - * - Simple Scalable Profile, Levels 1-2 - * - Core Profile, Levels 1-2 - * - Main Profile, Levels 2-4 - * - N-bit Profile, Level 2 - * - Scalable Texture Profile, Level 1 - * - Simple Face Animation Profile, Levels 1-2 - * - Simple Face and Body Animation (FBA) Profile, Levels 1-2 - * - Basic Animated Texture Profile, Levels 1-2 - * - Hybrid Profile, Levels 1-2 - * - Advanced Real Time Simple Profiles, Levels 1-4 - * - Core Scalable Profile, Levels 1-3 - * - Advanced Coding Efficiency Profile, Levels 1-4 - * - Advanced Core Profile, Levels 1-2 - * - Advanced Scalable Texture, Levels 2-3 - */ -typedef enum OMX_VIDEO_MPEG4PROFILETYPE { - OMX_VIDEO_MPEG4ProfileSimple = 0x01, - OMX_VIDEO_MPEG4ProfileSimpleScalable = 0x02, - OMX_VIDEO_MPEG4ProfileCore = 0x04, - OMX_VIDEO_MPEG4ProfileMain = 0x08, - OMX_VIDEO_MPEG4ProfileNbit = 0x10, - OMX_VIDEO_MPEG4ProfileScalableTexture = 0x20, - OMX_VIDEO_MPEG4ProfileSimpleFace = 0x40, - OMX_VIDEO_MPEG4ProfileSimpleFBA = 0x80, - OMX_VIDEO_MPEG4ProfileBasicAnimated = 0x100, - OMX_VIDEO_MPEG4ProfileHybrid = 0x200, - OMX_VIDEO_MPEG4ProfileAdvancedRealTime = 0x400, - OMX_VIDEO_MPEG4ProfileCoreScalable = 0x800, - OMX_VIDEO_MPEG4ProfileAdvancedCoding = 0x1000, - OMX_VIDEO_MPEG4ProfileAdvancedCore = 0x2000, - OMX_VIDEO_MPEG4ProfileAdvancedScalable = 0x4000, - OMX_VIDEO_MPEG4ProfileAdvancedSimple = 0x8000, - OMX_VIDEO_MPEG4ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4PROFILETYPE; - - -/** - * MPEG-4 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG4LEVELTYPE { - OMX_VIDEO_MPEG4Level0 = 0x01, /**< Level 0 */ - OMX_VIDEO_MPEG4Level0b = 0x02, /**< Level 0b */ - OMX_VIDEO_MPEG4Level1 = 0x04, /**< Level 1 */ - OMX_VIDEO_MPEG4Level2 = 0x08, /**< Level 2 */ - OMX_VIDEO_MPEG4Level3 = 0x10, /**< Level 3 */ - OMX_VIDEO_MPEG4Level4 = 0x20, /**< Level 4 */ - OMX_VIDEO_MPEG4Level4a = 0x40, /**< Level 4a */ - OMX_VIDEO_MPEG4Level5 = 0x80, /**< Level 5 */ - OMX_VIDEO_MPEG4LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4LEVELTYPE; - - -/** - * MPEG-4 configuration. This structure handles configuration options - * which are specific to MPEG4 algorithms - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header (H263+ - * Annex K). Put zero if not used - * bSVH : Enable Short Video Header mode - * bGov : Flag to enable GOV - * nPFrames : Number of P frames between each I frame (also called - * GOV period) - * nBFrames : Number of B frames between each I frame - * nIDCVLCThreshold : Value of intra DC VLC threshold - * bACPred : Flag to use ac prediction - * nMaxPacketSize : Maximum size of packet in bytes. - * nTimeIncRes : Used to pass VOP time increment resolution for MPEG4. - * Interpreted as described in MPEG4 standard. - * eProfile : MPEG-4 profile(s) to use. - * eLevel : MPEG-4 level(s) to use. - * nAllowedPictureTypes : Specifies the picture types allowed in the bitstream - * nHeaderExtension : Specifies the number of consecutive video packet - * headers within a VOP - * bReversibleVLC : Specifies whether reversible variable length coding - * is in use - */ -typedef struct OMX_VIDEO_PARAM_MPEG4TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_BOOL bSVH; - OMX_BOOL bGov; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_U32 nIDCVLCThreshold; - OMX_BOOL bACPred; - OMX_U32 nMaxPacketSize; - OMX_U32 nTimeIncRes; - OMX_VIDEO_MPEG4PROFILETYPE eProfile; - OMX_VIDEO_MPEG4LEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_U32 nHeaderExtension; - OMX_BOOL bReversibleVLC; -} OMX_VIDEO_PARAM_MPEG4TYPE; - - -/** - * WMV Versions - */ -typedef enum OMX_VIDEO_WMVFORMATTYPE { - OMX_VIDEO_WMVFormatUnused = 0x01, /**< Format unused or unknown */ - OMX_VIDEO_WMVFormat7 = 0x02, /**< Windows Media Video format 7 */ - OMX_VIDEO_WMVFormat8 = 0x04, /**< Windows Media Video format 8 */ - OMX_VIDEO_WMVFormat9 = 0x08, /**< Windows Media Video format 9 */ - OMX_VIDEO_WMFFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_WMFFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_WMVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_WMVFORMATTYPE; - - -/** - * WMV Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of WMV stream / data - */ -typedef struct OMX_VIDEO_PARAM_WMVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_WMVFORMATTYPE eFormat; -} OMX_VIDEO_PARAM_WMVTYPE; - - -/** - * Real Video Version - */ -typedef enum OMX_VIDEO_RVFORMATTYPE { - OMX_VIDEO_RVFormatUnused = 0, /**< Format unused or unknown */ - OMX_VIDEO_RVFormat8, /**< Real Video format 8 */ - OMX_VIDEO_RVFormat9, /**< Real Video format 9 */ - OMX_VIDEO_RVFormatG2, /**< Real Video Format G2 */ - OMX_VIDEO_RVFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_RVFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_RVFORMATTYPE; - - -/** - * Real Video Params - * - * STUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of RV stream / data - * nBitsPerPixel : Bits per pixel coded in the frame - * nPaddedWidth : Padded width in pixel of a video frame - * nPaddedHeight : Padded Height in pixels of a video frame - * nFrameRate : Rate of video in frames per second - * nBitstreamFlags : Flags which internal information about the bitstream - * nBitstreamVersion : Bitstream version - * nMaxEncodeFrameSize: Max encoded frame size - * bEnablePostFilter : Turn on/off post filter - * bEnableTemporalInterpolation : Turn on/off temporal interpolation - * bEnableLatencyMode : When enabled, the decoder does not display a decoded - * frame until it has detected that no enhancement layer - * frames or dependent B frames will be coming. This - * detection usually occurs when a subsequent non-B - * frame is encountered - */ -typedef struct OMX_VIDEO_PARAM_RVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_RVFORMATTYPE eFormat; - OMX_U16 nBitsPerPixel; - OMX_U16 nPaddedWidth; - OMX_U16 nPaddedHeight; - OMX_U32 nFrameRate; - OMX_U32 nBitstreamFlags; - OMX_U32 nBitstreamVersion; - OMX_U32 nMaxEncodeFrameSize; - OMX_BOOL bEnablePostFilter; - OMX_BOOL bEnableTemporalInterpolation; - OMX_BOOL bEnableLatencyMode; -} OMX_VIDEO_PARAM_RVTYPE; - - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_AVCPROFILETYPE { - OMX_VIDEO_AVCProfileBaseline = 0x01, /**< Baseline profile */ - OMX_VIDEO_AVCProfileMain = 0x02, /**< Main profile */ - OMX_VIDEO_AVCProfileExtended = 0x04, /**< Extended profile */ - OMX_VIDEO_AVCProfileHigh = 0x08, /**< High profile */ - OMX_VIDEO_AVCProfileHigh10 = 0x10, /**< High 10 profile */ - OMX_VIDEO_AVCProfileHigh422 = 0x20, /**< High 4:2:2 profile */ - OMX_VIDEO_AVCProfileHigh444 = 0x40, /**< High 4:4:4 profile */ - OMX_VIDEO_AVCProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_AVCPROFILETYPE; - - -/** - * AVC level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_AVCLEVELTYPE { - OMX_VIDEO_AVCLevel1 = 0x01, /**< Level 1 */ - OMX_VIDEO_AVCLevel1b = 0x02, /**< Level 1b */ - OMX_VIDEO_AVCLevel11 = 0x04, /**< Level 1.1 */ - OMX_VIDEO_AVCLevel12 = 0x08, /**< Level 1.2 */ - OMX_VIDEO_AVCLevel13 = 0x10, /**< Level 1.3 */ - OMX_VIDEO_AVCLevel2 = 0x20, /**< Level 2 */ - OMX_VIDEO_AVCLevel21 = 0x40, /**< Level 2.1 */ - OMX_VIDEO_AVCLevel22 = 0x80, /**< Level 2.2 */ - OMX_VIDEO_AVCLevel3 = 0x100, /**< Level 3 */ - OMX_VIDEO_AVCLevel31 = 0x200, /**< Level 3.1 */ - OMX_VIDEO_AVCLevel32 = 0x400, /**< Level 3.2 */ - OMX_VIDEO_AVCLevel4 = 0x800, /**< Level 4 */ - OMX_VIDEO_AVCLevel41 = 0x1000, /**< Level 4.1 */ - OMX_VIDEO_AVCLevel42 = 0x2000, /**< Level 4.2 */ - OMX_VIDEO_AVCLevel5 = 0x4000, /**< Level 5 */ - OMX_VIDEO_AVCLevel51 = 0x8000, /**< Level 5.1 */ - OMX_VIDEO_AVCLevel52 = 0x10000, /**< Level 5.2 */ - OMX_VIDEO_AVCLevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLEVELTYPE; - - -/** - * AVC loop filter modes - * - * OMX_VIDEO_AVCLoopFilterEnable : Enable - * OMX_VIDEO_AVCLoopFilterDisable : Disable - * OMX_VIDEO_AVCLoopFilterDisableSliceBoundary : Disabled on slice boundaries - */ -typedef enum OMX_VIDEO_AVCLOOPFILTERTYPE { - OMX_VIDEO_AVCLoopFilterEnable = 0, - OMX_VIDEO_AVCLoopFilterDisable, - OMX_VIDEO_AVCLoopFilterDisableSliceBoundary, - OMX_VIDEO_AVCLoopFilterKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLoopFilterVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLoopFilterMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLOOPFILTERTYPE; - - -/** - * AVC params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header, put - * zero if not used - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * bUseHadamard : Enable/disable Hadamard transform - * nRefFrames : Max number of reference frames to use for inter - * motion search (1-16) - * nRefIdxTrailing : Pic param set ref frame index (index into ref - * frame buffer of trailing frames list), B frame - * support - * nRefIdxForward : Pic param set ref frame index (index into ref - * frame buffer of forward frames list), B frame - * support - * bEnableUEP : Enable/disable unequal error protection. This - * is only valid of data partitioning is enabled. - * bEnableFMO : Enable/disable flexible macroblock ordering - * bEnableASO : Enable/disable arbitrary slice ordering - * bEnableRS : Enable/disable sending of redundant slices - * eProfile : AVC profile(s) to use - * eLevel : AVC level(s) to use - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bFrameMBsOnly : specifies that every coded picture of the - * coded video sequence is a coded frame - * containing only frame macroblocks - * bMBAFF : Enable/disable switching between frame and - * field macroblocks within a picture - * bEntropyCodingCABAC : Entropy decoding method to be applied for the - * syntax elements for which two descriptors appear - * in the syntax tables - * bWeightedPPrediction : Enable/disable weighted prediction shall not - * be applied to P and SP slices - * nWeightedBipredicitonMode : Default weighted prediction is applied to B - * slices - * bconstIpred : Enable/disable intra prediction - * bDirect8x8Inference : Specifies the method used in the derivation - * process for luma motion vectors for B_Skip, - * B_Direct_16x16 and B_Direct_8x8 as specified - * in subclause 8.4.1.2 of the AVC spec - * bDirectSpatialTemporal : Flag indicating spatial or temporal direct - * mode used in B slice coding (related to - * bDirect8x8Inference) . Spatial direct mode is - * more common and should be the default. - * nCabacInitIdx : Index used to init CABAC contexts - * eLoopFilterMode : Enable/disable loop filter - */ -typedef struct OMX_VIDEO_PARAM_AVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_BOOL bUseHadamard; - OMX_U32 nRefFrames; - OMX_U32 nRefIdx10ActiveMinus1; - OMX_U32 nRefIdx11ActiveMinus1; - OMX_BOOL bEnableUEP; - OMX_BOOL bEnableFMO; - OMX_BOOL bEnableASO; - OMX_BOOL bEnableRS; - OMX_VIDEO_AVCPROFILETYPE eProfile; - OMX_VIDEO_AVCLEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bFrameMBsOnly; - OMX_BOOL bMBAFF; - OMX_BOOL bEntropyCodingCABAC; - OMX_BOOL bWeightedPPrediction; - OMX_U32 nWeightedBipredicitonMode; - OMX_BOOL bconstIpred ; - OMX_BOOL bDirect8x8Inference; - OMX_BOOL bDirectSpatialTemporal; - OMX_U32 nCabacInitIdc; - OMX_VIDEO_AVCLOOPFILTERTYPE eLoopFilterMode; -} OMX_VIDEO_PARAM_AVCTYPE; - -typedef struct OMX_VIDEO_PARAM_PROFILELEVELTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 eProfile; /**< type is OMX_VIDEO_AVCPROFILETYPE, OMX_VIDEO_H263PROFILETYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 eLevel; /**< type is OMX_VIDEO_AVCLEVELTYPE, OMX_VIDEO_H263LEVELTYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 nProfileIndex; /**< Used to query for individual profile support information, - This parameter is valid only for - OMX_IndexParamVideoProfileLevelQuerySupported index, - For all other indices this parameter is to be ignored. */ -} OMX_VIDEO_PARAM_PROFILELEVELTYPE; - -/** - * Structure for dynamically configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * nEncodeBitrate : Target average bitrate to be generated in bps - */ -typedef struct OMX_VIDEO_CONFIG_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEncodeBitrate; -} OMX_VIDEO_CONFIG_BITRATETYPE; - -/** - * Defines Encoder Frame Rate setting - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * xEncodeFramerate : Encoding framerate represented in Q16 format - */ -typedef struct OMX_CONFIG_FRAMERATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 xEncodeFramerate; /* Q16 format */ -} OMX_CONFIG_FRAMERATETYPE; - -typedef struct OMX_CONFIG_INTRAREFRESHVOPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL IntraRefreshVOP; -} OMX_CONFIG_INTRAREFRESHVOPTYPE; - -typedef struct OMX_CONFIG_MACROBLOCKERRORMAPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nErrMapSize; /* Size of the Error Map in bytes */ - OMX_U8 ErrMap[1]; /* Error map hint */ -} OMX_CONFIG_MACROBLOCKERRORMAPTYPE; - -typedef struct OMX_CONFIG_MBERRORREPORTINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; -} OMX_CONFIG_MBERRORREPORTINGTYPE; - -typedef struct OMX_PARAM_MACROBLOCKSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nMacroblocks; -} OMX_PARAM_MACROBLOCKSTYPE; - -/** - * AVC Slice Mode modes - * - * OMX_VIDEO_SLICEMODE_AVCDefault : Normal frame encoding, one slice per frame - * OMX_VIDEO_SLICEMODE_AVCMBSlice : NAL mode, number of MBs per frame - * OMX_VIDEO_SLICEMODE_AVCByteSlice : NAL mode, number of bytes per frame - */ -typedef enum OMX_VIDEO_AVCSLICEMODETYPE { - OMX_VIDEO_SLICEMODE_AVCDefault = 0, - OMX_VIDEO_SLICEMODE_AVCMBSlice, - OMX_VIDEO_SLICEMODE_AVCByteSlice, - OMX_VIDEO_SLICEMODE_AVCKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_SLICEMODE_AVCVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_SLICEMODE_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCSLICEMODETYPE; - -/** - * AVC FMO Slice Mode Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNumSliceGroups : Specifies the number of slice groups - * nSliceGroupMapType : Specifies the type of slice groups - * eSliceMode : Specifies the type of slice - */ -typedef struct OMX_VIDEO_PARAM_AVCSLICEFMO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U8 nNumSliceGroups; - OMX_U8 nSliceGroupMapType; - OMX_VIDEO_AVCSLICEMODETYPE eSliceMode; -} OMX_VIDEO_PARAM_AVCSLICEFMO; - -/** - * AVC IDR Period Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nIDRPeriod : Specifies periodicity of IDR frames - * nPFrames : Specifies internal of coding Intra frames - */ -typedef struct OMX_VIDEO_CONFIG_AVCINTRAPERIOD { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIDRPeriod; - OMX_U32 nPFrames; -} OMX_VIDEO_CONFIG_AVCINTRAPERIOD; - -/** - * AVC NAL Size Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNaluBytes : Specifies the NAL unit size - */ -typedef struct OMX_VIDEO_CONFIG_NALSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNaluBytes; -} OMX_VIDEO_CONFIG_NALSIZE; - - -/** - * Deinterlace Config - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nEnable : Specifies to enable deinterlace - */ -typedef struct OMX_VIDEO_CONFIG_DEINTERLACE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEnable; -} OMX_VIDEO_CONFIG_DEINTERLACE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_VideoExt.h b/third_party/openmax/include/OMX_VideoExt.h deleted file mode 100644 index 5bf6fd4878..0000000000 --- a/third_party/openmax/include/OMX_VideoExt.h +++ /dev/null @@ -1,166 +0,0 @@ -/* - * Copyright (c) 2010 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_VideoExt.h - OpenMax IL version 1.1.2 - * The OMX_VideoExt header file contains extensions to the - * definitions used by both the application and the component to - * access video items. - */ - -#ifndef OMX_VideoExt_h -#define OMX_VideoExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - -/** NALU Formats */ -typedef enum OMX_NALUFORMATSTYPE { - OMX_NaluFormatStartCodes = 1, - OMX_NaluFormatOneNaluPerBuffer = 2, - OMX_NaluFormatOneByteInterleaveLength = 4, - OMX_NaluFormatTwoByteInterleaveLength = 8, - OMX_NaluFormatFourByteInterleaveLength = 16, - OMX_NaluFormatCodingMax = 0x7FFFFFFF -} OMX_NALUFORMATSTYPE; - -/** NAL Stream Format */ -typedef struct OMX_NALSTREAMFORMATTYPE{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_NALUFORMATSTYPE eNaluFormat; -} OMX_NALSTREAMFORMATTYPE; - -/** VP8 profiles */ -typedef enum OMX_VIDEO_VP8PROFILETYPE { - OMX_VIDEO_VP8ProfileMain = 0x01, - OMX_VIDEO_VP8ProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_VP8PROFILETYPE; - -/** VP8 levels */ -typedef enum OMX_VIDEO_VP8LEVELTYPE { - OMX_VIDEO_VP8Level_Version0 = 0x01, - OMX_VIDEO_VP8Level_Version1 = 0x02, - OMX_VIDEO_VP8Level_Version2 = 0x04, - OMX_VIDEO_VP8Level_Version3 = 0x08, - OMX_VIDEO_VP8LevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8LevelMax = 0x7FFFFFFF -} OMX_VIDEO_VP8LEVELTYPE; - -/** VP8 Param */ -typedef struct OMX_VIDEO_PARAM_VP8TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_VP8PROFILETYPE eProfile; - OMX_VIDEO_VP8LEVELTYPE eLevel; - OMX_U32 nDCTPartitions; - OMX_BOOL bErrorResilientMode; -} OMX_VIDEO_PARAM_VP8TYPE; - -/** Structure for configuring VP8 reference frames */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bPreviousFrameRefresh; - OMX_BOOL bGoldenFrameRefresh; - OMX_BOOL bAlternateFrameRefresh; - OMX_BOOL bUsePreviousFrame; - OMX_BOOL bUseGoldenFrame; - OMX_BOOL bUseAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMETYPE; - -/** Structure for querying VP8 reference frame type */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bIsIntraFrame; - OMX_BOOL bIsGoldenOrAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE; - -/** HEVC Profiles */ -typedef enum OMX_VIDEO_HEVCPROFILETYPE { - OMX_VIDEO_HEVCProfileMain = 0x01, - OMX_VIDEO_HEVCProfileMain10 = 0x02, - OMX_VIDEO_HEVCProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCPROFILETYPE; - -/** HEVC levels */ -typedef enum OMX_VIDEO_HEVCLEVELTYPE { - OMX_VIDEO_HEVCLevel_Version0 = 0x0, - OMX_VIDEO_HEVCMainTierLevel1 = 0x1, - OMX_VIDEO_HEVCHighTierLevel1 = 0x2, - OMX_VIDEO_HEVCMainTierLevel2 = 0x4, - OMX_VIDEO_HEVCHighTierLevel2 = 0x8, - OMX_VIDEO_HEVCMainTierLevel21 = 0x10, - OMX_VIDEO_HEVCHighTierLevel21 = 0x20, - OMX_VIDEO_HEVCMainTierLevel3 = 0x40, - OMX_VIDEO_HEVCHighTierLevel3 = 0x80, - OMX_VIDEO_HEVCMainTierLevel31 = 0x100, - OMX_VIDEO_HEVCHighTierLevel31 = 0x200, - OMX_VIDEO_HEVCMainTierLevel4 = 0x400, - OMX_VIDEO_HEVCHighTierLevel4 = 0x800, - OMX_VIDEO_HEVCMainTierLevel41 = 0x1000, - OMX_VIDEO_HEVCHighTierLevel41 = 0x2000, - OMX_VIDEO_HEVCMainTierLevel5 = 0x4000, - OMX_VIDEO_HEVCHighTierLevel5 = 0x8000, - OMX_VIDEO_HEVCMainTierLevel51 = 0x10000, - OMX_VIDEO_HEVCHighTierLevel51 = 0x20000, - OMX_VIDEO_HEVCMainTierLevel52 = 0x40000, - OMX_VIDEO_HEVCHighTierLevel52 = 0x80000, - OMX_VIDEO_HEVCMainTierLevel6 = 0x100000, - OMX_VIDEO_HEVCHighTierLevel6 = 0x200000, - OMX_VIDEO_HEVCMainTierLevel61 = 0x400000, - OMX_VIDEO_HEVCHighTierLevel61 = 0x800000, - OMX_VIDEO_HEVCMainTierLevel62 = 0x1000000, - OMX_VIDEO_HEVCLevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCLEVELTYPE; - -/** HEVC Param */ -typedef struct OMX_VIDEO_PARAM_HEVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_HEVCPROFILETYPE eProfile; - OMX_VIDEO_HEVCLEVELTYPE eLevel; -} OMX_VIDEO_PARAM_HEVCTYPE; - - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_VideoExt_h */ -/* File EOF */ diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index 040c2e18f0..67bc1ffb7b 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -11,10 +11,7 @@ V4L2_BUF_FLAG_KEYFRAME = 8 def writer(fn, addr, sock_name): import cereal.messaging as messaging - HEADER = b"\x00\x00\x00\x01\x40\x01\x0c\x01\xff\xff\x01\x60\x00\x00\x03\x00\xb0\x00\x00\x03\x00\x00\x03\x00\x96\xac\x09\x00\x00\x00\x01\x42\x01\x01\x01\x60\x00\x00\x03\x00\xb0\x00\x00\x03\x00\x00\x03\x00\x96\xa0\x03\xd0\x80\x13\x07\x1b\x2e\x5a\xee\x4c\x92\xea\x00\xbb\x42\x84\xa0\x00\x00\x00\x01\x44\x01\xc0\xe2\x4f\x09\xc1\x80\xc6\x08\x40\x00" fifo_file = open(fn, "wb") - fifo_file.write(HEADER) - fifo_file.flush() os.environ["ZMQ"] = "1" messaging.context = messaging.Context() @@ -26,23 +23,25 @@ def writer(fn, addr, sock_name): msgs = messaging.drain_sock(sock, wait_for_one=True) for evt in msgs: evta = getattr(evt, evt.which()) - lat = ((evt.logMonoTime/1e9) - (evta.timestampEof/1e6))*1000 - print("%2d %4d %.3f %.3f latency %.2f ms" % (len(msgs), evta.idx, evt.logMonoTime/1e9, evta.timestampEof/1e6, lat), len(evta.data), sock_name) - if evta.idx != 0 and evta.idx != (last_idx+1): + lat = ((evt.logMonoTime/1e9) - (evta.idx.timestampEof/1e9))*1000 + print("%2d %4d %.3f %.3f latency %.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, lat), len(evta.data), sock_name) + if evta.idx.encodeId != 0 and evta.idx.encodeId != (last_idx+1): print("DROP!") - last_idx = evta.idx - if evta.flags & V4L2_BUF_FLAG_KEYFRAME or evta.flags == 0x7f001030: + last_idx = evta.idx.encodeId + if evta.idx.flags & V4L2_BUF_FLAG_KEYFRAME: + fifo_file.write(evta.header) seen_iframe = True if not seen_iframe: print("waiting for iframe") continue fifo_file.write(evta.data) - fifo_file.flush() + +FFMPEG_OPTIONS = {"probesize": "32", "flags": "low_delay"} def decoder_nvidia(fn, vipc_server, vst, yuv=True, rgb=False): sys.path.append("/raid.dell2/PyNvCodec") import PyNvCodec as nvc # pylint: disable=import-error - decoder = nvc.PyNvDecoder(fn, 0, {"probesize": "32"}) + decoder = nvc.PyNvDecoder(fn, 0, FFMPEG_OPTIONS) cc1 = nvc.ColorspaceConversionContext(nvc.ColorSpace.BT_709, nvc.ColorRange.JPEG) if rgb: @@ -72,7 +71,7 @@ def decoder_nvidia(fn, vipc_server, vst, yuv=True, rgb=False): def decoder_ffmpeg(fn, vipc_server, vst, yuv=True, rgb=False): import av # pylint: disable=import-error - container = av.open(fn, options={"probesize": "32"}) + container = av.open(fn, options=FFMPEG_OPTIONS) cnt = 0 for frame in container.decode(video=0): if rgb: @@ -87,6 +86,7 @@ import argparse if __name__ == "__main__": parser = argparse.ArgumentParser(description='Decode video streams and broacast on VisionIPC') parser.add_argument("addr", help="Address of comma 3") + parser.add_argument('--pipes', action='store_true', help='Only create pipes') parser.add_argument('--nvidia', action='store_true', help='Use nvidia instead of ffmpeg') parser.add_argument('--rgb', action='store_true', help='Also broadcast RGB') parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") @@ -112,7 +112,9 @@ if __name__ == "__main__": os.unlink(FIFO_NAME) os.mkfifo(FIFO_NAME) multiprocessing.Process(target=writer, args=(FIFO_NAME, sys.argv[1], k)).start() - if args.nvidia: + if args.pipes: + print("connect to", FIFO_NAME) + elif args.nvidia: multiprocessing.Process(target=decoder_nvidia, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start() else: multiprocessing.Process(target=decoder_ffmpeg, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start() From ec7cd74dc37caad9a281f70fa1bfcb12535efeb9 Mon Sep 17 00:00:00 2001 From: Comma Device Date: Sat, 30 Apr 2022 09:31:31 -0700 Subject: [PATCH 004/391] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index aea23111ee..a1f97eaca2 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit aea23111ee0a08efb549d1d318405b9af8f456d9 +Subproject commit a1f97eaca24a04e778c2326e6c992b1e3943429a From 0bbfc63c9c11bab25767ef10cea5b70b520cba7f Mon Sep 17 00:00:00 2001 From: Keyvan Fatehi Date: Sun, 1 May 2022 18:41:50 -0700 Subject: [PATCH 005/391] body: add fuelGauge to body carState (#24386) --- cereal | 2 +- selfdrive/car/body/carstate.py | 2 ++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index a1f97eaca2..8e9e9d3cee 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit a1f97eaca24a04e778c2326e6c992b1e3943429a +Subproject commit 8e9e9d3ceef850c3c759ac39737bbfbd5801cea5 diff --git a/selfdrive/car/body/carstate.py b/selfdrive/car/body/carstate.py index 520aab8fa1..9d9e9b84c3 100644 --- a/selfdrive/car/body/carstate.py +++ b/selfdrive/car/body/carstate.py @@ -20,6 +20,8 @@ class CarState(CarStateBase): ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], cp.vl['VAR_VALUES']['FAULT']]) + ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 + # irrelevant for non-car ret.gearShifter = car.CarState.GearShifter.drive ret.cruiseState.enabled = True diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index b870f98460..bf3824224d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -d17ecea1f071007193a8a1e1ececf78c96b9deac \ No newline at end of file +9385014c512d253655f574d77fe1e07558f4157d \ No newline at end of file From 39cf8624355ae30c3b90b4c8d56ba44b665dda10 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 1 May 2022 18:52:32 -0700 Subject: [PATCH 006/391] lines for mypy report --- .pre-commit-config.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index cf41b28a90..10762162a7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -21,11 +21,12 @@ repos: - id: mypy exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/' additional_dependencies: ['git+https://github.com/numpy/numpy-stubs', 'types-requests', 'types-atomicwrites', - 'types-pycurl', 'types-certifi'] + 'types-pycurl', 'types-certifi', 'lxml'] args: - --warn-unused-ignores - --warn-redundant-casts - --warn-unreachable + #- --html-report=/home/batman/openpilot - repo: https://github.com/PyCQA/flake8 rev: 4.0.1 hooks: From 7ac92938d246030095c2928d24d55d74b57565db Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Mon, 2 May 2022 03:57:39 +0200 Subject: [PATCH 007/391] UI: remove unused lock and fence (#24355) --- selfdrive/ui/qt/widgets/cameraview.cc | 7 ------- selfdrive/ui/qt/widgets/cameraview.h | 9 --------- 2 files changed, 16 deletions(-) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index d817d55568..cb978182db 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -214,16 +214,9 @@ void CameraViewWidget::paintGL() { glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - std::lock_guard lk(lock); - if (latest_frame == nullptr) return; glViewport(0, 0, width(), height()); - // sync with the PBO - if (wait_fence) { - wait_fence->wait(); - } - glBindVertexArray(frame_vao); glUseProgram(program->programId()); diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 1f19ea157b..6873e8e991 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -35,19 +35,10 @@ protected: virtual void updateFrameMat(int w, int h); void vipcThread(); - struct WaitFence { - WaitFence() { sync = glFenceSync(GL_SYNC_GPU_COMMANDS_COMPLETE, 0); } - ~WaitFence() { glDeleteSync(sync); } - void wait() { glWaitSync(sync, 0, GL_TIMEOUT_IGNORED); } - GLsync sync = 0; - }; - bool zoomed_view; - std::mutex lock; VisionBuf *latest_frame = nullptr; GLuint frame_vao, frame_vbo, frame_ibo; mat4 frame_mat; - std::unique_ptr wait_fence; std::unique_ptr program; QColor bg = QColor("#000000"); From b361632cc23d059023614d665376a4706986299b Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 2 May 2022 10:24:33 +0200 Subject: [PATCH 008/391] bump cereal --- cereal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cereal b/cereal index 8e9e9d3cee..3b5860e0cd 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 8e9e9d3ceef850c3c759ac39737bbfbd5801cea5 +Subproject commit 3b5860e0cdf0be0022b00e88343d06e35ef849fc From 6e0c25d654771ad13cd276481fc652989f681c2c Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Mon, 2 May 2022 12:04:23 +0200 Subject: [PATCH 009/391] camerad: cleanup DM exposure and move into camera_qcom2.cc (#24391) * camerad: cleanup DM exposure and move into camera_qcom2.cc * remove include --- selfdrive/camerad/cameras/camera_common.cc | 42 ---------------------- selfdrive/camerad/cameras/camera_common.h | 1 - selfdrive/camerad/cameras/camera_qcom2.cc | 23 +++++++++++- 3 files changed, 22 insertions(+), 44 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index c37846870e..eecc57b037 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -13,7 +13,6 @@ #include "selfdrive/camerad/imgproc/utils.h" #include "selfdrive/common/clutil.h" #include "selfdrive/common/modeldata.h" -#include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" @@ -377,47 +376,6 @@ std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, pro return std::thread(processing_thread, cameras, cs, callback); } -static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { - static const bool is_rhd = Params().getBool("IsRHD"); - struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; - const CameraBuf *b = &c->buf; - - int x_offset = 0, y_offset = 0; - int frame_width = b->rgb_width, frame_height = b->rgb_height; - - - ExpRect def_rect; - if (Hardware::TICI()) { - x_offset = 630, y_offset = 156; - frame_width = 668, frame_height = frame_width / 1.33; - def_rect = {96, 1832, 2, 242, 1148, 4}; - } else { - def_rect = {is_rhd ? 0 : b->rgb_width * 3 / 5, is_rhd ? b->rgb_width * 2 / 5 : b->rgb_width, 2, - b->rgb_height / 3, b->rgb_height, 1}; - } - - static ExpRect rect = def_rect; - - camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); -} - -void common_process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - int j = Hardware::TICI() ? 1 : 3; - if (cnt % j == 0) { - s->sm->update(0); - driver_cam_auto_exposure(c, *(s->sm)); - } - MessageBuilder msg; - auto framed = msg.initEvent().initDriverCameraState(); - framed.setFrameType(cereal::FrameData::FrameType::FRONT); - fill_frame_data(framed, c->buf.cur_frame_data); - if (env_send_driver) { - framed.setImage(get_frame_image(&c->buf)); - } - s->pm->send("driverCameraState", msg); -} - - void camerad_thread() { cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); #ifdef QCOM2 diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index e415f80982..066af0b75c 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -131,7 +131,6 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr kj::Array get_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); -void common_process_driver_camera(MultiCameraState *s, CameraState *c, int cnt); void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx); void cameras_open(MultiCameraState *s); diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index 1d092eb6a6..e04cab10fe 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -1114,6 +1114,27 @@ void camera_autoexposure(CameraState *s, float grey_frac) { s->set_camera_exposure(grey_frac); } +static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { + struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; + const CameraBuf *b = &c->buf; + static ExpRect rect = {96, 1832, 2, 242, 1148, 4}; + camera_autoexposure(c, set_exposure_target(b, rect.x1, rect.x2, rect.x_skip, rect.y1, rect.y2, rect.y_skip)); +} + +static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { + s->sm->update(0); + driver_cam_auto_exposure(c, *(s->sm)); + + MessageBuilder msg; + auto framed = msg.initEvent().initDriverCameraState(); + framed.setFrameType(cereal::FrameData::FrameType::FRONT); + fill_frame_data(framed, c->buf.cur_frame_data); + if (env_send_driver) { + framed.setImage(get_frame_image(&c->buf)); + } + s->pm->send("driverCameraState", msg); +} + // called by processing_thread void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { const CameraBuf *b = &c->buf; @@ -1139,7 +1160,7 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { void cameras_run(MultiCameraState *s) { LOG("-- Starting threads"); std::vector threads; - if (s->driver_cam.enabled) threads.push_back(start_process_thread(s, &s->driver_cam, common_process_driver_camera)); + if (s->driver_cam.enabled) threads.push_back(start_process_thread(s, &s->driver_cam, process_driver_camera)); if (s->road_cam.enabled) threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); if (s->wide_road_cam.enabled) threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); From 4190d2608a536e1b28fb999a72bbf5b80810743d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 2 May 2022 13:34:31 -0700 Subject: [PATCH 010/391] Change safetyParam to uint16_t (#24376) * bump panda & cereal * bump panda * rest of references * regen TOYOTA with safety param 578, TOYOTA2 with 329 * regen rest of routes * update ref * bump cereal --- cereal | 2 +- panda | 2 +- selfdrive/boardd/boardd.cc | 4 ++-- selfdrive/boardd/panda.cc | 6 ++---- selfdrive/boardd/panda.h | 2 +- selfdrive/test/process_replay/ref_commit | 2 +- selfdrive/test/process_replay/test_processes.py | 8 ++++---- 7 files changed, 12 insertions(+), 14 deletions(-) diff --git a/cereal b/cereal index 3b5860e0cd..c9cdd7e398 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3b5860e0cdf0be0022b00e88343d06e35ef849fc +Subproject commit c9cdd7e398768252891de2f740ee4f65db9c39da diff --git a/panda b/panda index 326cc2a8db..168b0db6a7 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 326cc2a8dbabbfe6c442f4b0192b18178a83b6a6 +Subproject commit 168b0db6a7ed53124a34ba2c2db03e7dd5b5dc26 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 5b44f4d60b..4af69ec271 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -135,7 +135,7 @@ bool safety_setter_thread(std::vector pandas) { util::sleep_for(20); } - pandas[0]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1); + pandas[0]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1U); std::string params; LOGW("waiting for params to set safety model"); @@ -156,7 +156,7 @@ bool safety_setter_thread(std::vector pandas) { capnp::FlatArrayMessageReader cmsg(aligned_buf.align(params.data(), params.size())); cereal::CarParams::Reader car_params = cmsg.getRoot(); cereal::CarParams::SafetyModel safety_model; - uint32_t safety_param; + uint16_t safety_param; auto safety_configs = car_params.getSafetyConfigs(); uint16_t alternative_experience = car_params.getAlternativeExperience(); diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 1c287fc57e..536cbd5b7e 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -247,10 +247,8 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length return transferred; } -void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint32_t safety_param) { - // FIXME: last two bytes must be empty - assert((safety_param >> 16) == 0U); - usb_write(0xdc, (uint16_t)safety_model, (uint16_t)safety_param); +void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param) { + usb_write(0xdc, (uint16_t)safety_model, safety_param); } void Panda::set_alternative_experience(uint16_t alternative_experience) { diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index 9bbeee86b4..23a10d5850 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -73,7 +73,7 @@ class Panda { // Panda functionality cereal::PandaState::PandaType get_hw_type(); - void set_safety_model(cereal::CarParams::SafetyModel safety_model, uint32_t safety_param=0U); + void set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param=0U); void set_alternative_experience(uint16_t alternative_experience); void set_rtc(struct tm sys_time); struct tm get_rtc(); diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bf3824224d..2d44d34690 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -9385014c512d253655f574d77fe1e07558f4157d \ No newline at end of file +fd3aebd002a93ebccfef95643f87e8d5c464f2da \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index c59fe197a4..4f1f11eaf7 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -33,11 +33,11 @@ original_segments = [ segments = [ ("BODY", "bd6a637565e91581|2022-04-04--22-05-08--0"), ("HYUNDAI", "fakedata|2022-01-20--17-49-04--0"), - ("TOYOTA", "fakedata|2022-04-28--18-59-34--0"), - ("TOYOTA2", "fakedata|2022-04-28--15-52-38--0"), - ("TOYOTA3", "fakedata|2022-04-13--19-09-53--0"), + ("TOYOTA", "fakedata|2022-04-29--15-57-12--0"), + ("TOYOTA2", "fakedata|2022-04-29--16-08-01--0"), + ("TOYOTA3", "fakedata|2022-04-29--16-17-39--0"), ("HONDA", "fakedata|2022-01-20--17-56-40--0"), - ("HONDA2", "fakedata|2022-04-13--19-23-30--0"), + ("HONDA2", "fakedata|2022-04-29--16-31-55--0"), ("CHRYSLER", "fakedata|2022-01-20--18-00-11--0"), ("SUBARU", "fakedata|2022-01-20--18-01-57--0"), ("GM", "fakedata|2022-01-20--18-03-41--0"), From 055f5b2a09d70f9992a1f1fb3e6735da9497e29a Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 2 May 2022 13:37:04 -0700 Subject: [PATCH 011/391] bump panda --- panda | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/panda b/panda index 168b0db6a7..eb662e4e50 160000 --- a/panda +++ b/panda @@ -1 +1 @@ -Subproject commit 168b0db6a7ed53124a34ba2c2db03e7dd5b5dc26 +Subproject commit eb662e4e5014a3fc3c04512d708f61080c7707c1 From 8cdeaf9aee158bf11869132f82863bec4489e4f9 Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Mon, 2 May 2022 14:42:18 -0700 Subject: [PATCH 012/391] Latcontrol torque: update tuning (#24357) * Little more chill * Update ref * Update refs --- selfdrive/car/toyota/interface.py | 6 +++--- selfdrive/car/toyota/tunes.py | 4 ++-- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 872a27c645..433058b3c0 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -47,7 +47,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 ret.mass = 4387. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE) + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.8, FRICTION=0.06) elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False @@ -55,7 +55,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.88 # 14.5 is spec end-to-end tire_stiffness_factor = 0.5533 ret.mass = 3650. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.5, FRICTION=0.06) + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.8, FRICTION=0.06) elif candidate == CAR.COROLLA: ret.wheelbase = 2.70 @@ -136,7 +136,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.9 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=3.0, FRICTION=0.08) + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.0, FRICTION=0.07) elif candidate in (CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_ESH): stop_and_go = True diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 8ea1d6547f..50b03b85ad 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -54,9 +54,9 @@ def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=.1): if name == LatTunes.TORQUE: tune.init('torque') tune.torque.useSteeringAngle = True - tune.torque.kp = 2.0 / MAX_LAT_ACCEL + tune.torque.kp = 1.0 / MAX_LAT_ACCEL tune.torque.kf = 1.0 / MAX_LAT_ACCEL - tune.torque.ki = 0.5 / MAX_LAT_ACCEL + tune.torque.ki = 0.25 / MAX_LAT_ACCEL tune.torque.friction = FRICTION elif name == LatTunes.INDI_PRIUS: tune.init('indi') diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 2d44d34690..1dbcdfc7d6 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -fd3aebd002a93ebccfef95643f87e8d5c464f2da \ No newline at end of file +7057499e945105b919d7706b25ded4fe38b9884d \ No newline at end of file From 603942ffe0f5f0dba9f14f1293306bc0482e0032 Mon Sep 17 00:00:00 2001 From: Dylan Herman Date: Mon, 2 May 2022 18:48:04 -0500 Subject: [PATCH 013/391] enable numpy mypy typing (#24387) * enable numpy mypy typing * remove --warn-return-any * merge conflict and syntax * merge conflict * merge conflict * add type to img var --- .pre-commit-config.yaml | 5 ++--- common/transformations/orientation.py | 3 ++- common/window.py | 4 ++-- mypy.ini | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 10762162a7..912ba1344e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -20,12 +20,11 @@ repos: hooks: - id: mypy exclude: '^(pyextra/)|(cereal/)|(rednose/)|(panda/)|(laika/)|(opendbc/)|(laika_repo/)|(rednose_repo/)/' - additional_dependencies: ['git+https://github.com/numpy/numpy-stubs', 'types-requests', 'types-atomicwrites', - 'types-pycurl', 'types-certifi', 'lxml'] + additional_dependencies: ['lxml', 'numpy', 'types-atomicwrites', 'types-pycurl', 'types-requests', 'types-certifi'] args: - - --warn-unused-ignores - --warn-redundant-casts - --warn-unreachable + - --warn-unused-ignores #- --html-report=/home/batman/openpilot - repo: https://github.com/PyCQA/flake8 rev: 4.0.1 diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py index 415e247ab2..134442b624 100644 --- a/common/transformations/orientation.py +++ b/common/transformations/orientation.py @@ -1,5 +1,6 @@ # pylint: skip-file import numpy as np +from typing import Callable from common.transformations.transformations import (ecef_euler_from_ned_single, euler2quat_single, @@ -11,7 +12,7 @@ from common.transformations.transformations import (ecef_euler_from_ned_single, rot2quat_single) -def numpy_wrap(function, input_shape, output_shape): +def numpy_wrap(function, input_shape, output_shape) -> Callable[..., np.ndarray]: """Wrap a function to take either an input or list of inputs and return the correct shape""" def f(*inps): *args, inp = inps diff --git a/common/window.py b/common/window.py index ce1eecb881..613b3b201b 100644 --- a/common/window.py +++ b/common/window.py @@ -2,7 +2,7 @@ import sys import pygame # pylint: disable=import-error import cv2 # pylint: disable=import-error -class Window(): +class Window: def __init__(self, w, h, caption="window", double=False, halve=False): self.w = w self.h = h @@ -54,7 +54,7 @@ class Window(): if __name__ == "__main__": import numpy as np win = Window(200, 200, double=True) - img = np.zeros((200, 200, 3), np.uint8) + img: np.ndarray = np.zeros((200, 200, 3), np.uint8) while 1: print("draw") img += 1 diff --git a/mypy.ini b/mypy.ini index 66b82bd5df..e2da60f926 100644 --- a/mypy.ini +++ b/mypy.ini @@ -1,4 +1,4 @@ [mypy] python_version = 3.8 ignore_missing_imports = True - +plugins = numpy.typing.mypy_plugin From 5b105facaee86fcd1eb58bccfa1d7d7d9f02a6df Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 2 May 2022 18:05:00 -0700 Subject: [PATCH 014/391] Add ACC faulted status to carState (#24399) * add accFaulted bool to carState * same for VW * remove import * bump * move to common * bump cereal to master --- cereal | 2 +- selfdrive/car/gm/carstate.py | 6 +++--- selfdrive/car/gm/interface.py | 5 +---- selfdrive/car/interfaces.py | 2 ++ selfdrive/car/volkswagen/carstate.py | 6 +++--- selfdrive/car/volkswagen/interface.py | 4 ---- 6 files changed, 10 insertions(+), 15 deletions(-) diff --git a/cereal b/cereal index c9cdd7e398..39cbdbfecf 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c9cdd7e398768252891de2f740ee4f65db9c39da +Subproject commit 39cbdbfecf542104f71ecb16d2d1dfd7375dbf5b diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index b94fd0f2ab..65ce2e3421 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -62,14 +62,14 @@ class CarState(CarStateBase): ret.parkingBrake = pt_cp.vl["EPBStatus"]["EPBClosed"] == 1 ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 - self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] + ret.accFaulted = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED # Regen braking is braking if self.car_fingerprint == CAR.VOLT: ret.brakePressed = ret.brakePressed or pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 - ret.cruiseState.enabled = self.pcm_acc_status != AccState.OFF - ret.cruiseState.standstill = self.pcm_acc_status == AccState.STANDSTILL + ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF + ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL return ret diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index 64ec9d4242..d00708c336 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -4,8 +4,7 @@ from math import fabs from common.conversions import Conversions as CV from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config -from selfdrive.car.gm.values import CAR, CruiseButtons, \ - AccState, CarControllerParams +from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams from selfdrive.car.interfaces import CarInterfaceBase ButtonType = car.CarState.ButtonEvent.Type @@ -190,8 +189,6 @@ class CarInterface(CarInterfaceBase): events.add(EventName.belowEngageSpeed) if ret.cruiseState.standstill: events.add(EventName.resumeRequired) - if self.CS.pcm_acc_status == AccState.FAULTED: - events.add(EventName.accFaulted) if ret.vEgo < self.CP.minSteerSpeed: events.add(car.CarEvent.EventName.belowSteerSpeed) diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 23822fe454..1ee237fe36 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -159,6 +159,8 @@ class CarInterfaceBase(ABC): events.add(EventName.brakeHold) if cs_out.parkingBrake: events.add(EventName.parkBrake) + if cs_out.accFaulted: + events.add(EventName.accFaulted) # Handle permanent and temporary steering faults self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index dfd6a0031f..4193030d87 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -93,12 +93,11 @@ class CarState(CarStateBase): ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) # Update ACC radar status. - self.tsk_status = pt_cp.vl["TSK_06"]["TSK_Status"] - if self.tsk_status == 2: + if pt_cp.vl["TSK_06"]["TSK_Status"] == 2: # ACC okay and enabled, but not currently engaged ret.cruiseState.available = True ret.cruiseState.enabled = False - elif self.tsk_status in (3, 4, 5): + elif pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5): # ACC okay and enabled, currently regulating speed (3) or driver accel override (4) or overrun coast-down (5) ret.cruiseState.available = True ret.cruiseState.enabled = True @@ -106,6 +105,7 @@ class CarState(CarStateBase): # ACC okay but disabled (1), or a radar visibility or other fault/disruption (6 or 7) ret.cruiseState.available = False ret.cruiseState.enabled = False + ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) # Update ACC setpoint. When the setpoint is zero or there's an error, the # radar sends a set-speed of ~90.69 m/s / 203mph. diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index f849d912a0..3a0d7c8ce8 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -177,10 +177,6 @@ class CarInterface(CarInterfaceBase): events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic]) - # Vehicle health and operation safety checks - if self.CS.tsk_status in (6, 7): - events.add(EventName.accFaulted) - # Low speed steer alert hysteresis logic if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 1.): self.low_speed_alert = True From d7c6121ba826a0646db8fadf9bd0b89f153c5576 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 2 May 2022 19:18:50 -0700 Subject: [PATCH 015/391] UI: better double click on touch screens (#24400) * UI: better double click on touch screens * lower * just right Co-authored-by: Comma Device --- selfdrive/ui/ui | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/ui/ui b/selfdrive/ui/ui index 68c8c2cad5..16ddbab050 100755 --- a/selfdrive/ui/ui +++ b/selfdrive/ui/ui @@ -2,4 +2,5 @@ cd "$(dirname "$0")" export LD_LIBRARY_PATH="/system/lib64:$LD_LIBRARY_PATH" export QT_PLUGIN_PATH="../../third_party/qt-plugins/$(uname -m)" +export QT_DBL_CLICK_DIST=150 exec ./_ui From 061b18805e131aeff6582730d1b6d2994ce7f985 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 2 May 2022 21:34:06 -0700 Subject: [PATCH 016/391] UI: add battery percent to body (#24401) * UI: add battery percent to body * little smaller Co-authored-by: Comma Device --- selfdrive/ui/qt/body.cc | 32 +++++++++++++++++++++++++++++++- selfdrive/ui/qt/body.h | 2 ++ 2 files changed, 33 insertions(+), 1 deletion(-) diff --git a/selfdrive/ui/qt/body.cc b/selfdrive/ui/qt/body.cc index 08d3611b46..a83d749577 100644 --- a/selfdrive/ui/qt/body.cc +++ b/selfdrive/ui/qt/body.cc @@ -2,6 +2,8 @@ #include +#include + BodyWindow::BodyWindow(QWidget *parent) : QLabel(parent) { awake = new QMovie("../assets/body/awake.gif"); awake->setCacheMode(QMovie::CacheAll); @@ -19,18 +21,46 @@ BodyWindow::BodyWindow(QWidget *parent) : QLabel(parent) { QObject::connect(uiState(), &UIState::uiUpdate, this, &BodyWindow::updateState); } +void BodyWindow::paintEvent(QPaintEvent *event) { + QLabel::paintEvent(event); + + QPainter p(this); + p.setRenderHint(QPainter::Antialiasing); + p.setPen(Qt::NoPen); + + // draw battery level + const int offset = 90; + const int radius = 60 / 2; + const int levels = 5; + const float interval = 1. / levels; + for (int i = 0; i < levels; i++) { + float level = 1.0 - (i+1)*interval; + float perc = (fuel >= level) ? 1.0 : 0.35; + + p.setBrush(QColor(255, 255, 255, 255 * perc)); + QPoint pt(width() - (i*offset + offset / 2), offset / 2); + p.drawEllipse(pt, radius, radius); + } +} + + void BodyWindow::updateState(const UIState &s) { if (!isVisible()) { return; } const SubMaster &sm = *(s.sm); + auto cs = sm["carState"].getCarState(); + + fuel = cs.getFuelGauge(); // TODO: use carState.standstill when that's fixed - const bool standstill = std::abs(sm["carState"].getCarState().getVEgo()) < 0.01; + const bool standstill = std::abs(cs.getVEgo()) < 0.01; QMovie *m = standstill ? sleep : awake; if (m != movie()) { setMovie(m); movie()->start(); } + + update(); } diff --git a/selfdrive/ui/qt/body.h b/selfdrive/ui/qt/body.h index 7f352715df..c1138b8703 100644 --- a/selfdrive/ui/qt/body.h +++ b/selfdrive/ui/qt/body.h @@ -12,7 +12,9 @@ public: BodyWindow(QWidget* parent = 0); private: + float fuel = 1.0; QMovie *awake, *sleep; + void paintEvent(QPaintEvent*) override; private slots: void updateState(const UIState &s); From 77a6f3d034a7b17d70b750b9ea454310f4b8edf1 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Tue, 3 May 2022 14:09:17 +0200 Subject: [PATCH 017/391] delay bz2 compression from logging to uploading (#24392) * remove log_name * log without compression * fix tests * remove extension for bootlog * another test fix * uploader compresses * also compress in athena * only compress qlog * more generic check in do_upload * fix bootlog compression * lower loggerd cpu usage * dont link against bz2 * set core affinity to little cluster * handle old files --- selfdrive/athena/athenad.py | 41 ++++++++++++++++++++---- selfdrive/athena/tests/test_athenad.py | 3 +- selfdrive/loggerd/SConscript | 4 +-- selfdrive/loggerd/bootlog.cc | 4 +-- selfdrive/loggerd/logger.cc | 11 +++---- selfdrive/loggerd/logger.h | 32 ++++-------------- selfdrive/loggerd/loggerd.cc | 2 +- selfdrive/loggerd/tests/test_encoder.py | 2 +- selfdrive/loggerd/tests/test_logger.cc | 10 +++--- selfdrive/loggerd/tests/test_loggerd.py | 6 ++-- selfdrive/loggerd/tests/test_uploader.py | 13 ++++---- selfdrive/loggerd/uploader.py | 21 ++++++++++-- selfdrive/test/process_replay/regen.py | 6 ++-- selfdrive/test/test_onroad.py | 10 +++--- 14 files changed, 96 insertions(+), 69 deletions(-) diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 919cf0c04e..b9c9acb465 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import base64 +import bz2 import hashlib import io import json @@ -30,7 +31,7 @@ from common.api import Api from common.basedir import PERSIST from common.file_helpers import CallbackReader from common.params import Params -from common.realtime import sec_since_boot +from common.realtime import sec_since_boot, set_core_affinity from selfdrive.hardware import HARDWARE, PC, TICI from selfdrive.loggerd.config import ROOT from selfdrive.loggerd.xattr_cache import getxattr, setxattr @@ -64,6 +65,13 @@ UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', ' cur_upload_items: Dict[int, Any] = {} + +def strip_bz2_extension(fn): + if fn.endswith('.bz2'): + return fn[:-4] + return fn + + class AbortTransferException(Exception): pass @@ -227,14 +235,29 @@ def upload_handler(end_event: threading.Event) -> None: def _do_upload(upload_item, callback=None): - with open(upload_item.path, "rb") as f: - size = os.fstat(f.fileno()).st_size + path = upload_item.path + compress = False + + # If file does not exist, but does exist without the .bz2 extension we will compress on the fly + if not os.path.exists(path) and os.path.exists(strip_bz2_extension(path)): + path = strip_bz2_extension(path) + compress = True + + with open(path, "rb") as f: + if compress: + cloudlog.event("athena.upload_handler.compress", fn=path, fn_orig=upload_item.path) + data = bz2.compress(f.read()) + size = len(data) + data = io.BytesIO(data) + else: + size = os.fstat(f.fileno()).st_size + data = f if callback: - f = CallbackReader(f, callback, size) + data = CallbackReader(data, callback, size) return requests.put(upload_item.url, - data=f, + data=data, headers={**upload_item.headers, 'Content-Length': str(size)}, timeout=30) @@ -335,8 +358,9 @@ def uploadFilesToUrls(files_data): if len(fn) == 0 or fn[0] == '/' or '..' in fn or 'url' not in file: failed.append(fn) continue + path = os.path.join(ROOT, fn) - if not os.path.exists(path): + if not os.path.exists(path) and not os.path.exists(strip_bz2_extension(path)): failed.append(fn) continue @@ -680,6 +704,11 @@ def backoff(retries): def main(): + try: + set_core_affinity([0, 1, 2, 3]) + except Exception: + cloudlog.exception("failed to set core affinity") + params = Params() dongle_id = params.get("DongleId", encoding='utf-8') UploadQueueCache.initialize(upload_queue) diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index 1742ed4347..b6457ca01d 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -81,7 +81,8 @@ class TestAthenadMethods(unittest.TestCase): def test_listDataDirectory(self): route = '2021-03-29--13-32-47' segments = [0, 1, 2, 3, 11] - filenames = ['qlog.bz2', 'qcamera.ts', 'rlog.bz2', 'fcamera.hevc', 'ecamera.hevc', 'dcamera.hevc'] + + filenames = ['qlog', 'qcamera.ts', 'rlog', 'fcamera.hevc', 'ecamera.hevc', 'dcamera.hevc'] files = [f'{route}--{s}/{f}' for s in segments for f in filenames] for file in files: fn = os.path.join(athenad.ROOT, file) diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 1efa99298b..7403dafb6d 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -3,7 +3,7 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc') libs = [common, cereal, messaging, visionipc, 'zmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', - 'yuv', 'bz2', 'OpenCL', 'pthread'] + 'yuv', 'OpenCL', 'pthread'] src = ['logger.cc', 'loggerd.cc', 'video_writer.cc', 'remote_encoder.cc'] if arch == "larch64": @@ -25,4 +25,4 @@ if arch == "larch64": env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): - env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_loggerd.cc', 'tests/test_logger.cc', env.Object('logger_util', '#/selfdrive/ui/replay/util.cc')], LIBS=libs + ['curl', 'crypto']) + env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_loggerd.cc', 'tests/test_logger.cc'], LIBS=libs + ['curl', 'crypto']) diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index e7ce308cec..e8fc955263 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -49,14 +49,14 @@ static kj::Array build_boot_log() { } int main(int argc, char** argv) { - const std::string path = LOG_ROOT + "/boot/" + logger_get_route_name() + ".bz2"; + const std::string path = LOG_ROOT + "/boot/" + logger_get_route_name(); LOGW("bootlog to %s", path.c_str()); // Open bootlog bool r = util::create_directories(LOG_ROOT + "/boot/", 0775); assert(r); - BZFile bz_file(path.c_str()); + RawFile bz_file(path.c_str()); // Write initdata bz_file.write(logger_build_init_data().asBytes()); diff --git a/selfdrive/loggerd/logger.cc b/selfdrive/loggerd/logger.cc index f2c34554e3..f8af20a406 100644 --- a/selfdrive/loggerd/logger.cc +++ b/selfdrive/loggerd/logger.cc @@ -109,13 +109,12 @@ static void lh_log_sentinel(LoggerHandle *h, SentinelType type) { // ***** logging functions ***** -void logger_init(LoggerState *s, const char* log_name, bool has_qlog) { +void logger_init(LoggerState *s, bool has_qlog) { pthread_mutex_init(&s->lock, NULL); s->part = -1; s->has_qlog = has_qlog; s->route_name = logger_get_route_name(); - snprintf(s->log_name, sizeof(s->log_name), "%s", log_name); s->init_data = logger_build_init_data(); } @@ -132,8 +131,8 @@ static LoggerHandle* logger_open(LoggerState *s, const char* root_path) { snprintf(h->segment_path, sizeof(h->segment_path), "%s/%s--%d", root_path, s->route_name.c_str(), s->part); - snprintf(h->log_path, sizeof(h->log_path), "%s/%s.bz2", h->segment_path, s->log_name); - snprintf(h->qlog_path, sizeof(h->qlog_path), "%s/qlog.bz2", h->segment_path); + snprintf(h->log_path, sizeof(h->log_path), "%s/rlog", h->segment_path); + snprintf(h->qlog_path, sizeof(h->qlog_path), "%s/qlog", h->segment_path); snprintf(h->lock_path, sizeof(h->lock_path), "%s.lock", h->log_path); h->end_sentinel_type = SentinelType::END_OF_SEGMENT; h->exit_signal = 0; @@ -144,9 +143,9 @@ static LoggerHandle* logger_open(LoggerState *s, const char* root_path) { if (lock_file == NULL) return NULL; fclose(lock_file); - h->log = std::make_unique(h->log_path); + h->log = std::make_unique(h->log_path); if (s->has_qlog) { - h->q_log = std::make_unique(h->qlog_path); + h->q_log = std::make_unique(h->qlog_path); } pthread_mutex_init(&h->lock, NULL); diff --git a/selfdrive/loggerd/logger.h b/selfdrive/loggerd/logger.h index bdda9d6917..288b884dd2 100644 --- a/selfdrive/loggerd/logger.h +++ b/selfdrive/loggerd/logger.h @@ -7,7 +7,6 @@ #include #include -#include #include #include @@ -20,42 +19,25 @@ const std::string LOG_ROOT = Path::log_root(); #define LOGGER_MAX_HANDLES 16 -class BZFile { +class RawFile { public: - BZFile(const char* path) { + RawFile(const char* path) { file = util::safe_fopen(path, "wb"); assert(file != nullptr); - int bzerror; - bz_file = BZ2_bzWriteOpen(&bzerror, file, 9, 0, 30); - assert(bzerror == BZ_OK); } - ~BZFile() { - int bzerror; - BZ2_bzWriteClose(&bzerror, bz_file, 0, nullptr, nullptr); - if (bzerror != BZ_OK) { - LOGE("BZ2_bzWriteClose error, bzerror=%d", bzerror); - } + ~RawFile() { util::safe_fflush(file); int err = fclose(file); assert(err == 0); } inline void write(void* data, size_t size) { - int bzerror; - do { - BZ2_bzWrite(&bzerror, bz_file, data, size); - } while (bzerror == BZ_IO_ERROR && errno == EINTR); - - if (bzerror != BZ_OK && !error_logged) { - LOGE("BZ2_bzWrite error, bzerror=%d", bzerror); - error_logged = true; - } + int written = util::safe_fwrite(data, 1, size, file); + assert(written == size); } inline void write(kj::ArrayPtr array) { write(array.begin(), array.size()); } private: - bool error_logged = false; FILE* file = nullptr; - BZFILE* bz_file = nullptr; }; typedef cereal::Sentinel::SentinelType SentinelType; @@ -69,7 +51,7 @@ typedef struct LoggerHandle { char log_path[4096]; char qlog_path[4096]; char lock_path[4096]; - std::unique_ptr log, q_log; + std::unique_ptr log, q_log; } LoggerHandle; typedef struct LoggerState { @@ -86,7 +68,7 @@ typedef struct LoggerState { kj::Array logger_build_init_data(); std::string logger_get_route_name(); -void logger_init(LoggerState *s, const char* log_name, bool has_qlog); +void logger_init(LoggerState *s, bool has_qlog); int logger_next(LoggerState *s, const char* root_path, char* out_segment_path, size_t out_segment_path_len, int* out_part); diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index e6bc4fcfa5..8e488b4a93 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -217,7 +217,7 @@ void loggerd_thread() { LoggerdState s; // init logger - logger_init(&s.logger, "rlog", true); + logger_init(&s.logger, true); logger_rotate(&s); Params().put("CurrentRoute", s.logger.route_name); diff --git a/selfdrive/loggerd/tests/test_encoder.py b/selfdrive/loggerd/tests/test_encoder.py index 760c255443..88b06b4b4c 100755 --- a/selfdrive/loggerd/tests/test_encoder.py +++ b/selfdrive/loggerd/tests/test_encoder.py @@ -112,7 +112,7 @@ class TestEncoder(unittest.TestCase): # Check encodeIdx if encode_idx_name is not None: - rlog_path = f"{route_prefix_path}--{i}/rlog.bz2" + rlog_path = f"{route_prefix_path}--{i}/rlog" msgs = [m for m in LogReader(rlog_path) if m.which() == encode_idx_name] encode_msgs = [getattr(m, encode_idx_name) for m in msgs] diff --git a/selfdrive/loggerd/tests/test_logger.cc b/selfdrive/loggerd/tests/test_logger.cc index 21b1d711d8..2513e507a0 100644 --- a/selfdrive/loggerd/tests/test_logger.cc +++ b/selfdrive/loggerd/tests/test_logger.cc @@ -18,10 +18,10 @@ void verify_segment(const std::string &route_path, int segment, int max_segment, SentinelType begin_sentinel = segment == 0 ? SentinelType::START_OF_ROUTE : SentinelType::START_OF_SEGMENT; SentinelType end_sentinel = segment == max_segment - 1 ? SentinelType::END_OF_ROUTE : SentinelType::END_OF_SEGMENT; - REQUIRE(!util::file_exists(segment_path + "/rlog.bz2.lock")); - for (const char *fn : {"/rlog.bz2", "/qlog.bz2"}) { + REQUIRE(!util::file_exists(segment_path + "/rlog.lock")); + for (const char *fn : {"/rlog", "/qlog"}) { const std::string log_file = segment_path + fn; - std::string log = decompressBZ2(util::read_file(log_file)); + std::string log = util::read_file(log_file); REQUIRE(!log.empty()); int event_cnt = 0, i = 0; kj::ArrayPtr words((capnp::word *)log.data(), log.size() / sizeof(capnp::word)); @@ -70,7 +70,7 @@ TEST_CASE("logger") { ExitHandler do_exit; LoggerState logger = {}; - logger_init(&logger, "rlog", true); + logger_init(&logger, true); char segment_path[PATH_MAX] = {}; int segment = -1; @@ -78,7 +78,7 @@ TEST_CASE("logger") { const int segment_cnt = 100; for (int i = 0; i < segment_cnt; ++i) { REQUIRE(logger_next(&logger, log_root.c_str(), segment_path, sizeof(segment_path), &segment) == 0); - REQUIRE(util::file_exists(std::string(segment_path) + "/rlog.bz2.lock")); + REQUIRE(util::file_exists(std::string(segment_path) + "/rlog.lock")); REQUIRE(segment == i); write_msg(logger.cur_handle); } diff --git a/selfdrive/loggerd/tests/test_loggerd.py b/selfdrive/loggerd/tests/test_loggerd.py index 13e0b720d8..f9f938ae7a 100755 --- a/selfdrive/loggerd/tests/test_loggerd.py +++ b/selfdrive/loggerd/tests/test_loggerd.py @@ -108,7 +108,7 @@ class TestLoggerd(unittest.TestCase): os.environ["LOGGERD_TEST"] = "1" Params().put("RecordFront", "1") - expected_files = {"rlog.bz2", "qlog.bz2", "qcamera.ts", "fcamera.hevc", "dcamera.hevc"} + expected_files = {"rlog", "qlog", "qcamera.ts", "fcamera.hevc", "dcamera.hevc"} streams = [(VisionStreamType.VISION_STREAM_ROAD, tici_f_frame_size if TICI else eon_f_frame_size, "roadCameraState"), (VisionStreamType.VISION_STREAM_DRIVER, tici_d_frame_size if TICI else eon_d_frame_size, "driverCameraState")] if TICI: @@ -208,7 +208,7 @@ class TestLoggerd(unittest.TestCase): time.sleep(1) managed_processes["loggerd"].stop() - qlog_path = os.path.join(self._get_latest_log_dir(), "qlog.bz2") + qlog_path = os.path.join(self._get_latest_log_dir(), "qlog") lr = list(LogReader(qlog_path)) # check initData and sentinel @@ -254,7 +254,7 @@ class TestLoggerd(unittest.TestCase): time.sleep(2) managed_processes["loggerd"].stop() - lr = list(LogReader(os.path.join(self._get_latest_log_dir(), "rlog.bz2"))) + lr = list(LogReader(os.path.join(self._get_latest_log_dir(), "rlog"))) # check initData and sentinel self._check_init_data(lr) diff --git a/selfdrive/loggerd/tests/test_uploader.py b/selfdrive/loggerd/tests/test_uploader.py index 01b529468b..dd81108700 100755 --- a/selfdrive/loggerd/tests/test_uploader.py +++ b/selfdrive/loggerd/tests/test_uploader.py @@ -54,11 +54,11 @@ class TestUploader(UploaderTestCase): def gen_files(self, lock=False, boot=True): f_paths = list() - for t in ["qlog.bz2", "rlog.bz2", "dcamera.hevc", "fcamera.hevc"]: + for t in ["qlog", "rlog", "dcamera.hevc", "fcamera.hevc"]: f_paths.append(self.make_file_with_data(self.seg_dir, t, 1, lock=lock)) if boot: - f_paths.append(self.make_file_with_data("boot", f"{self.seg_dir}.bz2", 1, lock=lock)) + f_paths.append(self.make_file_with_data("boot", f"{self.seg_dir}", 1, lock=lock)) return f_paths def gen_order(self, seg1, seg2, boot=True): @@ -84,7 +84,7 @@ class TestUploader(UploaderTestCase): self.assertFalse(len(log_handler.upload_order) < len(exp_order), "Some files failed to upload") self.assertFalse(len(log_handler.upload_order) > len(exp_order), "Some files were uploaded twice") for f_path in exp_order: - self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not uploaded") + self.assertTrue(getxattr(os.path.join(self.root, f_path.replace('.bz2', '')), uploader.UPLOAD_ATTR_NAME), "All files not uploaded") self.assertTrue(log_handler.upload_order == exp_order, "Files uploaded in wrong order") @@ -103,7 +103,7 @@ class TestUploader(UploaderTestCase): self.assertFalse(len(log_handler.upload_ignored) < len(exp_order), "Some files failed to ignore") self.assertFalse(len(log_handler.upload_ignored) > len(exp_order), "Some files were ignored twice") for f_path in exp_order: - self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not ignored") + self.assertTrue(getxattr(os.path.join(self.root, f_path.replace('.bz2', '')), uploader.UPLOAD_ATTR_NAME), "All files not ignored") self.assertTrue(log_handler.upload_ignored == exp_order, "Files ignored in wrong order") @@ -128,7 +128,7 @@ class TestUploader(UploaderTestCase): self.assertFalse(len(log_handler.upload_order) < len(exp_order), "Some files failed to upload") self.assertFalse(len(log_handler.upload_order) > len(exp_order), "Some files were uploaded twice") for f_path in exp_order: - self.assertTrue(getxattr(os.path.join(self.root, f_path), uploader.UPLOAD_ATTR_NAME), "All files not uploaded") + self.assertTrue(getxattr(os.path.join(self.root, f_path.replace('.bz2', '')), uploader.UPLOAD_ATTR_NAME), "All files not uploaded") self.assertTrue(log_handler.upload_order == exp_order, "Files uploaded in wrong order") @@ -143,8 +143,7 @@ class TestUploader(UploaderTestCase): self.join_thread() for f_path in f_paths: - self.assertFalse(getxattr(f_path, uploader.UPLOAD_ATTR_NAME), "File upload when locked") - + self.assertFalse(getxattr(f_path.replace('.bz2', ''), uploader.UPLOAD_ATTR_NAME), "File upload when locked") def test_clear_locks_on_startup(self): f_paths = self.gen_files(lock=True, boot=False) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 9e9dd0c79e..d13026c4b3 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import bz2 import json import os import random @@ -12,6 +13,7 @@ from cereal import log import cereal.messaging as messaging from common.api import Api from common.params import Params +from common.realtime import set_core_affinity from selfdrive.hardware import TICI from selfdrive.loggerd.xattr_cache import getxattr, setxattr from selfdrive.loggerd.config import ROOT @@ -69,7 +71,7 @@ class Uploader(): self.last_filename = "" self.immediate_folders = ["crash/", "boot/"] - self.immediate_priority = {"qlog.bz2": 0, "qcamera.ts": 1} + self.immediate_priority = {"qlog": 0, "qlog.bz2": 0, "qcamera.ts": 1} def get_upload_sort(self, name): if name in self.immediate_priority: @@ -149,7 +151,12 @@ class Uploader(): self.last_resp = FakeResponse() else: with open(fn, "rb") as f: - self.last_resp = requests.put(url, data=f, headers=headers, timeout=10) + data = f.read() + + if key.endswith('.bz2') and not fn.endswith('.bz2'): + data = bz2.compress(data) + + self.last_resp = requests.put(url, data=data, headers=headers, timeout=10) except Exception as e: self.last_exc = (e, traceback.format_exc()) raise @@ -212,7 +219,13 @@ class Uploader(): us.lastFilename = self.last_filename return msg + def uploader_fn(exit_event): + try: + set_core_affinity([0, 1, 2, 3]) + except Exception: + cloudlog.exception("failed to set core affinity") + clear_locks(ROOT) params = Params() @@ -247,6 +260,10 @@ def uploader_fn(exit_event): key, fn = d + # qlogs and bootlogs need to be compressed before uploading + if key.endswith('qlog') or (key.startswith('boot/') and not key.endswith('.bz2')): + key += ".bz2" + success = uploader.upload(key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) if success: backoff = 0.1 diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index 5084a40060..d8ca67dc33 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -256,7 +256,7 @@ def regen_segment(lr, frs=None, outdir=FAKEDATA): segment = params.get("CurrentRoute", encoding='utf-8') + "--0" seg_path = os.path.join(outdir, segment) # check to make sure openpilot is engaged in the route - if not check_enabled(LogReader(os.path.join(seg_path, "rlog.bz2"))): + if not check_enabled(LogReader(os.path.join(seg_path, "rlog"))): raise Exception(f"Route never enabled: {segment}") return seg_path @@ -268,11 +268,11 @@ def regen_and_save(route, sidx, upload=False, use_route_meta=False): lr = LogReader(r.log_paths()[args.seg]) fr = FrameReader(r.camera_paths()[args.seg]) else: - lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2") + lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog") fr = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc") rpath = regen_segment(lr, {'roadCameraState': fr}) - lr = LogReader(os.path.join(rpath, 'rlog.bz2')) + lr = LogReader(os.path.join(rpath, 'rlog2')) controls_state_active = [m.controlsState.active for m in lr if m.which() == 'controlsState'] assert any(controls_state_active), "Segment did not engage" diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 0fea95d0f5..830522ec5e 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -22,7 +22,7 @@ from tools.lib.logreader import LogReader # Baseline CPU usage by process PROCS = { "selfdrive.controls.controlsd": 31.0, - "./loggerd": 70.0, + "./loggerd": 50.0, "./camerad": 26.0, "./locationd": 9.1, "selfdrive.controls.plannerd": 11.7, @@ -108,9 +108,9 @@ class TestOnroad(unittest.TestCase): @classmethod def setUpClass(cls): if "DEBUG" in os.environ: - segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog.bz2")), Path(ROOT).iterdir()) + segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog")), Path(ROOT).iterdir()) segs = sorted(segs, key=lambda x: x.stat().st_mtime) - cls.lr = list(LogReader(os.path.join(segs[-1], "rlog.bz2"))) + cls.lr = list(LogReader(os.path.join(segs[-1], "rlog"))) return # setup env @@ -160,10 +160,10 @@ class TestOnroad(unittest.TestCase): if proc.wait(60) is None: proc.kill() - cls.lrs = [list(LogReader(os.path.join(str(s), "rlog.bz2"))) for s in cls.segments] + cls.lrs = [list(LogReader(os.path.join(str(s), "rlog"))) for s in cls.segments] # use the second segment by default as it's the first full segment - cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog.bz2"))) + cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog"))) def test_cloudlog_size(self): msgs = [m for m in self.lr if m.which() == 'logMessage'] From 05f606c8121c89990225ff873c2779fcb3790ead Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Tue, 3 May 2022 17:30:22 +0200 Subject: [PATCH 018/391] camerad: allow to log raw camera frames (#24393) * camerad: log raw camera frames with env var * dont qlog * cleaner * only road camera * use vision buf len * use static counter to handle frame skips * we already have cnt Co-authored-by: Willem Melching --- selfdrive/camerad/cameras/camera_common.cc | 13 +++++++++++++ selfdrive/camerad/cameras/camera_common.h | 3 +++ selfdrive/camerad/cameras/camera_qcom2.cc | 2 ++ 3 files changed, 18 insertions(+) diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index eecc57b037..77b0548873 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -146,6 +146,8 @@ bool CameraBuf::acquire() { double start_time = millis_since_boot(); + cur_camera_buf = &camera_bufs[cur_buf_idx]; + if (debayer) { float gain = 0.0; float black_level = 42.0; @@ -236,6 +238,17 @@ kj::Array get_frame_image(const CameraBuf *b) { return kj::mv(frame_image); } +kj::Array get_raw_frame_image(const CameraBuf *b) { + const uint8_t *dat = (const uint8_t *)b->cur_camera_buf->addr; + + kj::Array frame_image = kj::heapArray(b->cur_camera_buf->len); + uint8_t *resized_dat = frame_image.begin(); + + memcpy(resized_dat, dat, b->cur_camera_buf->len); + + return kj::mv(frame_image); +} + static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_width, int thumbnail_height) { // make the buffer big enough. jpeg_write_raw_data requires 16-pixels aligned height to be used. std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 066af0b75c..9c7bf6b034 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -47,6 +47,7 @@ const bool env_disable_road = getenv("DISABLE_ROAD") != NULL; const bool env_disable_wide_road = getenv("DISABLE_WIDE_ROAD") != NULL; const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL; const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; +const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; typedef void (*release_cb)(void *cookie, int buf_idx); @@ -111,6 +112,7 @@ public: FrameMetadata cur_frame_data; VisionBuf *cur_rgb_buf; VisionBuf *cur_yuv_buf; + VisionBuf *cur_camera_buf; std::unique_ptr camera_bufs; std::unique_ptr camera_bufs_metadata; int rgb_width, rgb_height, rgb_stride; @@ -129,6 +131,7 @@ typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data); kj::Array get_frame_image(const CameraBuf *b); +kj::Array get_raw_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index e04cab10fe..7120bf9576 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -1144,6 +1144,8 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { fill_frame_data(framed, b->cur_frame_data); if ((c == &s->road_cam && env_send_road) || (c == &s->wide_road_cam && env_send_wide_road)) { framed.setImage(get_frame_image(b)); + } else if (env_log_raw_frames && c == &s->road_cam && cnt % 100 == 5) { // no overlap with qlog decimation + framed.setImage(get_raw_frame_image(b)); } LOGT(c->buf.cur_frame_data.frame_id, "%s: Image set", c == &s->road_cam ? "RoadCamera" : "WideRoadCamera"); if (c == &s->road_cam) { From c994dfdd8af6b9ed8df5a7ee93dde45e84a1d6e2 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 3 May 2022 13:00:01 -0700 Subject: [PATCH 019/391] one day you'll be a submodule --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 06c6117b18..ce6114e58f 100644 --- a/.gitignore +++ b/.gitignore @@ -56,6 +56,7 @@ selfdrive/modeld/_dmonitoringmodeld /src/ one +body openpilot notebooks xx From 3f0b06b16e638036adb7fe5110b6b5c38d30f1fe Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 3 May 2022 13:17:24 -0700 Subject: [PATCH 020/391] Chrysler: clean up CarController (#24337) * clean up * max range is 15 * use wheel buttons counter and clean up * no * try spamming 10 times with next counter value * try 50 hz * this is dead code * revert behavior changes, just clean up * revert more * also that * no multiline can creation * sort imports --- selfdrive/car/chrysler/carcontroller.py | 45 ++++++++++++------------- selfdrive/car/chrysler/chryslercan.py | 2 +- selfdrive/car/chrysler/interface.py | 6 +--- 3 files changed, 23 insertions(+), 30 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 0648699f95..eda00a2ea1 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,16 +1,16 @@ from cereal import car +from opendbc.can.packer import CANPacker from selfdrive.car import apply_toyota_steer_torque_limits -from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, \ - create_wheel_buttons +from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, create_wheel_buttons from selfdrive.car.chrysler.values import CAR, CarControllerParams -from opendbc.can.packer import CANPacker -class CarController(): + +class CarController: def __init__(self, dbc_name, CP, VM): self.CP = CP self.apply_steer_last = 0 - self.ccframe = 0 - self.prev_frame = -1 + self.frame = 0 + self.prev_lkas_frame = -1 self.hud_count = 0 self.car_fingerprint = CP.carFingerprint self.gone_fast_yet = False @@ -18,12 +18,13 @@ class CarController(): self.packer = CANPacker(dbc_name) - def update(self, enabled, CS, actuators, pcm_cancel_cmd, hud_alert): + def update(self, CC, CS): # this seems needed to avoid steering faults and to force the sync with the EPS counter - frame = CS.lkas_counter - if self.prev_frame == frame: + if self.prev_lkas_frame == CS.lkas_counter: return car.CarControl.Actuators.new_message(), [] + actuators = CC.actuators + # steer torque new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, @@ -36,7 +37,7 @@ class CarController(): elif self.car_fingerprint in (CAR.PACIFICA_2019_HYBRID, CAR.PACIFICA_2020, CAR.JEEP_CHEROKEE_2019): if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): self.gone_fast_yet = False # < 14.5m/s stock turns off this bit, but fine down to 13.5 - lkas_active = moving_fast and enabled + lkas_active = moving_fast and CC.enabled if not lkas_active: apply_steer = 0 @@ -45,28 +46,24 @@ class CarController(): can_sends = [] - #*** control msgs *** + # *** control msgs *** - if pcm_cancel_cmd: + if CC.cruiseControl.cancel: # TODO: would be better to start from frame_2b3 - new_msg = create_wheel_buttons(self.packer, self.ccframe, cancel=True) - can_sends.append(new_msg) + can_sends.append(create_wheel_buttons(self.packer, self.frame, cancel=True)) # LKAS_HEARTBIT is forwarded by Panda so no need to send it here. # frame is 100Hz (0.01s period) - if (self.ccframe % 25 == 0): # 0.25s period - if (CS.lkas_car_model != -1): - new_msg = create_lkas_hud( - self.packer, CS.out.gearShifter, lkas_active, hud_alert, - self.hud_count, CS.lkas_car_model) - can_sends.append(new_msg) + if self.frame % 25 == 0: # 0.25s period + if CS.lkas_car_model != -1: + can_sends.append(create_lkas_hud(self.packer, CS.out.gearShifter, lkas_active, + CC.hudControl.visualAlert, self.hud_count, CS.lkas_car_model)) self.hud_count += 1 - new_msg = create_lkas_command(self.packer, int(apply_steer), self.gone_fast_yet, frame) - can_sends.append(new_msg) + can_sends.append(create_lkas_command(self.packer, int(apply_steer), self.gone_fast_yet, CS.lkas_counter)) - self.ccframe += 1 - self.prev_frame = frame + self.frame += 1 + self.prev_lkas_frame = CS.lkas_counter new_actuators = actuators.copy() new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 4d5226570c..33f614d75e 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -52,6 +52,6 @@ def create_wheel_buttons(packer, frame, cancel=False): # WHEEL_BUTTONS (571) Message sent to cancel ACC. values = { "ACC_CANCEL": cancel, - "COUNTER": frame % 10 + "COUNTER": frame % 10 # FIXME: this counter is wrong } return packer.make_can_msg("WHEEL_BUTTONS", 0, values) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 7751bd151b..55672dd4ab 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -65,8 +65,4 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c): - - if (self.CS.frame == -1): - return car.CarControl.Actuators.new_message(), [] # if we haven't seen a frame 220, then do not update. - - return self.CC.update(c.enabled, self.CS, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert) + return self.CC.update(c, self.CS) From 986a991a09cc38375ded9f9809388a4384abf169 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 3 May 2022 13:27:19 -0700 Subject: [PATCH 021/391] body: log charging status (#24409) * body: log charging status * update refs --- cereal | 2 +- selfdrive/car/body/carstate.py | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 39cbdbfecf..3f8210d1fd 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 39cbdbfecf542104f71ecb16d2d1dfd7375dbf5b +Subproject commit 3f8210d1fd3a2090aa1eea9b1c60050859874f1b diff --git a/selfdrive/car/body/carstate.py b/selfdrive/car/body/carstate.py index 9d9e9b84c3..dbbd85950d 100644 --- a/selfdrive/car/body/carstate.py +++ b/selfdrive/car/body/carstate.py @@ -20,6 +20,7 @@ class CarState(CarStateBase): ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], cp.vl['VAR_VALUES']['FAULT']]) + ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 # irrelevant for non-car diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 1dbcdfc7d6..c7cbe1da22 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -7057499e945105b919d7706b25ded4fe38b9884d \ No newline at end of file +7f1f4bd17965cc703b824ffb1870313bee93e2ec \ No newline at end of file From 9a44d4c4e0895f88dd5cd716ce3e2d6ebeab3457 Mon Sep 17 00:00:00 2001 From: ntegan1 Date: Tue, 3 May 2022 17:18:46 -0400 Subject: [PATCH 022/391] LatControlTorque: log desired/actual lateral accel (#24406) * log torque lateral accel * bump cereal * update refs Co-authored-by: Shane Smiskol --- cereal | 2 +- selfdrive/controls/lib/latcontrol_torque.py | 2 ++ selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 3f8210d1fd..5935572cee 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 3f8210d1fd3a2090aa1eea9b1c60050859874f1b +Subproject commit 5935572cee86f202e2524d5f388f9475f92cd649 diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index a73744de74..4e9d559798 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -73,6 +73,8 @@ class LatControlTorque(LatControl): pid_log.f = self.pid.f pid_log.output = -output_torque pid_log.saturated = self._check_saturation(self.steer_max - abs(output_torque) < 1e-3, CS) + pid_log.actualLateralAccel = actual_lateral_accel + pid_log.desiredLateralAccel = desired_lateral_accel # TODO left is positive in this convention return -output_torque, 0.0, pid_log diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index c7cbe1da22..5bed2e765c 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -7f1f4bd17965cc703b824ffb1870313bee93e2ec \ No newline at end of file +70d79fbcc2b9ab0af867a7d6f138b58bcaaa3aa8 \ No newline at end of file From 043a309d67da9c4d4671303b370e04aa29cd115d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 3 May 2022 16:51:44 -0700 Subject: [PATCH 023/391] ui: new notcar battery design (#24412) * ui: new notcar battery design * if charging * cleanup * remove that * slower * real colors * relative from left * fix that --- selfdrive/ui/qt/body.cc | 50 +++++++++++++++++++++++++++----------- selfdrive/ui/qt/body.h | 4 ++- selfdrive/ui/tests/body.py | 22 +++++++++++++++++ 3 files changed, 61 insertions(+), 15 deletions(-) create mode 100755 selfdrive/ui/tests/body.py diff --git a/selfdrive/ui/qt/body.cc b/selfdrive/ui/qt/body.cc index a83d749577..da87a7485a 100644 --- a/selfdrive/ui/qt/body.cc +++ b/selfdrive/ui/qt/body.cc @@ -1,10 +1,11 @@ #include "selfdrive/ui/qt/body.h" #include +#include #include -BodyWindow::BodyWindow(QWidget *parent) : QLabel(parent) { +BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QLabel(parent) { awake = new QMovie("../assets/body/awake.gif"); awake->setCacheMode(QMovie::CacheAll); sleep = new QMovie("../assets/body/sleep.gif"); @@ -26,20 +27,40 @@ void BodyWindow::paintEvent(QPaintEvent *event) { QPainter p(this); p.setRenderHint(QPainter::Antialiasing); + + p.translate(width() - 136, 16); + + // battery outline + detail + const QColor gray = QColor("#737373"); + p.setBrush(Qt::NoBrush); + p.setPen(QPen(gray, 4, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin)); + p.drawRoundedRect(2, 2, 78, 36, 8, 8); + p.setPen(Qt::NoPen); + p.setBrush(gray); + p.drawRoundedRect(84, 12, 6, 16, 4, 4); + p.drawRect(84, 12, 3, 16); - // draw battery level - const int offset = 90; - const int radius = 60 / 2; - const int levels = 5; - const float interval = 1. / levels; - for (int i = 0; i < levels; i++) { - float level = 1.0 - (i+1)*interval; - float perc = (fuel >= level) ? 1.0 : 0.35; - - p.setBrush(QColor(255, 255, 255, 255 * perc)); - QPoint pt(width() - (i*offset + offset / 2), offset / 2); - p.drawEllipse(pt, radius, radius); + // battery level + double fuel = std::clamp(fuel_filter.x(), 0.2f, 1.0f); + const int m = 5; // manual margin since we can't do an inner border + p.setPen(Qt::NoPen); + p.setBrush(fuel > 0.25 ? QColor("#32D74B") : QColor("#FF453A")); + p.drawRoundedRect(2 + m, 2 + m, (78 - 2*m)*fuel, 36 - 2*m, 4, 4); + + // charging status + if (charging) { + p.setPen(Qt::NoPen); + p.setBrush(Qt::white); + const QPolygonF charger({ + QPointF(12.31, 0), + QPointF(12.31, 16.92), + QPointF(18.46, 16.92), + QPointF(6.15, 40), + QPointF(6.15, 23.08), + QPointF(0, 23.08), + }); + p.drawPolygon(charger.translated(98, 0)); } } @@ -52,7 +73,8 @@ void BodyWindow::updateState(const UIState &s) { const SubMaster &sm = *(s.sm); auto cs = sm["carState"].getCarState(); - fuel = cs.getFuelGauge(); + charging = cs.getCharging(); + fuel_filter.update(cs.getFuelGauge()); // TODO: use carState.standstill when that's fixed const bool standstill = std::abs(cs.getVEgo()) < 0.01; diff --git a/selfdrive/ui/qt/body.h b/selfdrive/ui/qt/body.h index c1138b8703..cf1ffa191f 100644 --- a/selfdrive/ui/qt/body.h +++ b/selfdrive/ui/qt/body.h @@ -3,6 +3,7 @@ #include #include +#include "selfdrive/common/util.h" #include "selfdrive/ui/ui.h" class BodyWindow : public QLabel { @@ -12,7 +13,8 @@ public: BodyWindow(QWidget* parent = 0); private: - float fuel = 1.0; + bool charging = false; + FirstOrderFilter fuel_filter; QMovie *awake, *sleep; void paintEvent(QPaintEvent*) override; diff --git a/selfdrive/ui/tests/body.py b/selfdrive/ui/tests/body.py new file mode 100755 index 0000000000..c34e717eaf --- /dev/null +++ b/selfdrive/ui/tests/body.py @@ -0,0 +1,22 @@ +#!/usr/bin/env python3 +import time +import cereal.messaging as messaging + +if __name__ == "__main__": + while True: + pm = messaging.PubMaster(['carParams', 'carState']) + batt = 1. + while True: + msg = messaging.new_message('carParams') + msg.carParams.carName = "COMMA BODY" + msg.carParams.notCar = True + pm.send('carParams', msg) + + for b in range(100, 0, -1): + msg = messaging.new_message('carState') + msg.carState.charging = True + msg.carState.fuelGauge = b / 100. + pm.send('carState', msg) + time.sleep(0.1) + + time.sleep(1) From 0771addd144a6822fca8209be53994c0db009bbb Mon Sep 17 00:00:00 2001 From: Jason Young <46612682+jyoung8607@users.noreply.github.com> Date: Tue, 3 May 2022 19:03:17 -0500 Subject: [PATCH 024/391] update joystick README for webjoystick (#24413) --- tools/joystick/README.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/tools/joystick/README.md b/tools/joystick/README.md index 5a45785db6..c74e51146c 100644 --- a/tools/joystick/README.md +++ b/tools/joystick/README.md @@ -45,6 +45,17 @@ In order to use a joystick over the network, we need to run joystickd locally fr tools/joystick/joystickd.py ``` +### Web joystick on your mobile device + +A browser-based virtual joystick designed for touch screens. Starts automatically when installed on comma body (non-car robotics platform). +For cars, start the web joystick service manually via SSH before starting the car. + +```shell +tools/joystick/web.py +``` + +After starting the car/body, open the web joystick app at this URL: `http://[comma three IP address]:5000` + --- Now start your car and openpilot should go into joystick mode with an alert on startup! The status of the axes will display on the alert, while button statuses print in the shell. From cdf6338388c4f2e054de0e76eb1401a2993360ce Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 3 May 2022 23:30:35 -0700 Subject: [PATCH 025/391] manager: start process by callback (#24417) --- selfdrive/manager/manager.py | 7 +++---- selfdrive/manager/process.py | 22 ++++++++++------------ selfdrive/manager/process_config.py | 19 ++++++++++++++----- 3 files changed, 27 insertions(+), 21 deletions(-) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 1934da6701..cd7817fa97 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -128,17 +128,16 @@ def manager_thread() -> None: ignore.append("pandad") ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0] - ensure_running(managed_processes.values(), started=False, not_run=ignore) - sm = messaging.SubMaster(['deviceState', 'carParams'], poll=['deviceState']) pm = messaging.PubMaster(['managerState']) + ensure_running(managed_processes.values(), False, params=params, CP=sm['carParams'], not_run=ignore) + while True: sm.update() started = sm['deviceState'].started - driverview = params.get_bool("IsDriverViewEnabled") - ensure_running(managed_processes.values(), started=started, driverview=driverview, notcar=sm['carParams'].notCar, not_run=ignore) + ensure_running(managed_processes.values(), started, params=params, CP=sm['carParams'], not_run=ignore) running = ' '.join("%s%s\u001b[0m" % ("\u001b[32m" if p.proc.is_alive() else "\u001b[31m", p.name) for p in managed_processes.values() if p.proc) diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index 8bb160961f..e2bb41c217 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -4,7 +4,7 @@ import signal import struct import time import subprocess -from typing import Optional, List, ValuesView +from typing import Optional, Callable, List, ValuesView from abc import ABC, abstractmethod from multiprocessing import Process @@ -12,6 +12,7 @@ from setproctitle import setproctitle # pylint: disable=no-name-in-module import cereal.messaging as messaging import selfdrive.sentry as sentry +from cereal import car from common.basedir import BASEDIR from common.params import Params from common.realtime import sec_since_boot @@ -71,8 +72,7 @@ class ManagerProcess(ABC): sigkill = False onroad = True offroad = False - driverview = False - notcar = False + callback: Optional[Callable[[bool, Params, car.CarParams], bool]] = None proc: Optional[Process] = None enabled = True name = "" @@ -184,15 +184,14 @@ class ManagerProcess(ABC): class NativeProcess(ManagerProcess): - def __init__(self, name, cwd, cmdline, enabled=True, onroad=True, offroad=False, driverview=False, notcar=False, unkillable=False, sigkill=False, watchdog_max_dt=None): + def __init__(self, name, cwd, cmdline, enabled=True, onroad=True, offroad=False, callback=None, unkillable=False, sigkill=False, watchdog_max_dt=None): self.name = name self.cwd = cwd self.cmdline = cmdline self.enabled = enabled self.onroad = onroad self.offroad = offroad - self.driverview = driverview - self.notcar = notcar + self.callback = callback self.unkillable = unkillable self.sigkill = sigkill self.watchdog_max_dt = watchdog_max_dt @@ -217,14 +216,13 @@ class NativeProcess(ManagerProcess): class PythonProcess(ManagerProcess): - def __init__(self, name, module, enabled=True, onroad=True, offroad=False, driverview=False, notcar=False, unkillable=False, sigkill=False, watchdog_max_dt=None): + def __init__(self, name, module, enabled=True, onroad=True, offroad=False, callback=None, unkillable=False, sigkill=False, watchdog_max_dt=None): self.name = name self.module = module self.enabled = enabled self.onroad = onroad self.offroad = offroad - self.driverview = driverview - self.notcar = notcar + self.callback = callback self.unkillable = unkillable self.sigkill = sigkill self.watchdog_max_dt = watchdog_max_dt @@ -291,7 +289,7 @@ class DaemonProcess(ManagerProcess): pass -def ensure_running(procs: ValuesView[ManagerProcess], started: bool, driverview: bool=False, notcar: bool=False, +def ensure_running(procs: ValuesView[ManagerProcess], started: bool, params=None, CP: car.CarParams=None, not_run: Optional[List[str]]=None) -> None: if not_run is None: not_run = [] @@ -301,9 +299,9 @@ def ensure_running(procs: ValuesView[ManagerProcess], started: bool, driverview: run = any(( p.offroad and not started, p.onroad and started, - p.driverview and driverview, - p.notcar and notcar, )) + if p.callback is not None and None not in (params, CP): + run = run or p.callback(started, params, CP) # Conditions that block a process from starting run = run and not any(( diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 2e2747fecc..0979c67d70 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -1,16 +1,25 @@ import os +from cereal import car +from common.params import Params from selfdrive.hardware import TICI, PC from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess WEBCAM = os.getenv("USE_WEBCAM") is not None +def driverview(started: bool, params: Params, CP: car.CarParams) -> bool: + return params.get_bool("IsDriverViewEnabled") + +def notcar(started: bool, params: Params, CP: car.CarParams) -> bool: + return CP.notCar + + procs = [ DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), # due to qualcomm kernel bugs SIGKILLing camerad sometimes causes page table corruption - NativeProcess("camerad", "selfdrive/camerad", ["./camerad"], unkillable=True, driverview=True), + NativeProcess("camerad", "selfdrive/camerad", ["./camerad"], unkillable=True, callback=driverview), NativeProcess("clocksd", "selfdrive/clocksd", ["./clocksd"]), - NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), driverview=True), + NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), NativeProcess("logcatd", "selfdrive/logcatd", ["./logcatd"]), NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"]), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), @@ -25,7 +34,7 @@ procs = [ PythonProcess("calibrationd", "selfdrive.locationd.calibrationd"), PythonProcess("controlsd", "selfdrive.controls.controlsd"), PythonProcess("deleter", "selfdrive.loggerd.deleter", offroad=True), - PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), driverview=True), + PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", enabled=(not PC or WEBCAM), callback=driverview), PythonProcess("logmessaged", "selfdrive.logmessaged", offroad=True), PythonProcess("pandad", "selfdrive.boardd.pandad", offroad=True), PythonProcess("paramsd", "selfdrive.locationd.paramsd"), @@ -38,8 +47,8 @@ procs = [ PythonProcess("uploader", "selfdrive.loggerd.uploader", offroad=True), PythonProcess("statsd", "selfdrive.statsd", offroad=True), - NativeProcess("bridge", "cereal/messaging", ["./bridge"], onroad=False, notcar=True), - PythonProcess("webjoystick", "tools.joystick.web", onroad=False, notcar=True), + NativeProcess("bridge", "cereal/messaging", ["./bridge"], onroad=False, callback=notcar), + PythonProcess("webjoystick", "tools.joystick.web", onroad=False, callback=notcar), # Experimental PythonProcess("rawgpsd", "selfdrive.sensord.rawgps.rawgpsd", enabled=os.path.isfile("/persist/comma/use-quectel-rawgps")), From 670126cbf15ceecb03279e6fa9779798d905cb99 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 3 May 2022 23:46:59 -0700 Subject: [PATCH 026/391] body: opt-in logging (#24416) --- selfdrive/common/params.cc | 1 + selfdrive/manager/process_config.py | 5 +- selfdrive/ui/qt/body.cc | 74 ++++++++++++++++++++++++----- selfdrive/ui/qt/body.h | 15 +++++- 4 files changed, 80 insertions(+), 15 deletions(-) diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index bea12aca11..9cc7a113cb 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -103,6 +103,7 @@ std::unordered_map keys = { {"DoReboot", CLEAR_ON_MANAGER_START}, {"DoShutdown", CLEAR_ON_MANAGER_START}, {"DoUninstall", CLEAR_ON_MANAGER_START}, + {"EnableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"EnableWideCamera", CLEAR_ON_MANAGER_START}, {"EndToEndToggle", PERSISTENT}, {"ForcePowerDown", CLEAR_ON_MANAGER_START}, diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 0979c67d70..34b120efaf 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -13,6 +13,9 @@ def driverview(started: bool, params: Params, CP: car.CarParams) -> bool: def notcar(started: bool, params: Params, CP: car.CarParams) -> bool: return CP.notCar +def logging(started, params, CP: car.CarParams) -> bool: + run = (not CP.notCar) or params.get_bool("EnableLogging") + return started and run procs = [ DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), @@ -21,7 +24,7 @@ procs = [ NativeProcess("clocksd", "selfdrive/clocksd", ["./clocksd"]), NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), NativeProcess("logcatd", "selfdrive/logcatd", ["./logcatd"]), - NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"]), + NativeProcess("loggerd", "selfdrive/loggerd", ["./loggerd"], onroad=False, callback=logging), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), NativeProcess("navd", "selfdrive/ui/navd", ["./navd"], offroad=True), NativeProcess("proclogd", "selfdrive/proclogd", ["./proclogd"]), diff --git a/selfdrive/ui/qt/body.cc b/selfdrive/ui/qt/body.cc index da87a7485a..01b91571a4 100644 --- a/selfdrive/ui/qt/body.cc +++ b/selfdrive/ui/qt/body.cc @@ -4,33 +4,81 @@ #include #include +#include -BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QLabel(parent) { +#include "selfdrive/common/params.h" + +RecordButton::RecordButton(QWidget *parent) : QPushButton(parent) { + setCheckable(true); + setChecked(false); + setFixedSize(148, 148); +} + +void RecordButton::paintEvent(QPaintEvent *event) { + QPainter p(this); + p.setRenderHint(QPainter::Antialiasing); + + QPoint center(width() / 2, height() / 2); + + QColor bg(isChecked() ? "#FFFFFF" : "#404040"); + QColor accent(isChecked() ? "#FF0000" : "#FFFFFF"); + if (isDown()) { + accent.setAlphaF(0.7); + } + + p.setPen(Qt::NoPen); + p.setBrush(bg); + p.drawEllipse(center, 74, 74); + + p.setPen(QPen(accent, 6)); + p.setBrush(Qt::NoBrush); + p.drawEllipse(center, 42, 42); + + p.setPen(Qt::NoPen); + p.setBrush(accent); + p.drawEllipse(center, 22, 22); +} + + +BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QWidget(parent) { + QStackedLayout *layout = new QStackedLayout(this); + layout->setStackingMode(QStackedLayout::StackAll); + + QWidget *w = new QWidget; + QVBoxLayout *vlayout = new QVBoxLayout(w); + vlayout->setMargin(45); + layout->addWidget(w); + + // face + face = new QLabel(); + face->setAlignment(Qt::AlignCenter); + layout->addWidget(face); awake = new QMovie("../assets/body/awake.gif"); awake->setCacheMode(QMovie::CacheAll); sleep = new QMovie("../assets/body/sleep.gif"); sleep->setCacheMode(QMovie::CacheAll); - QPalette p(Qt::black); - setPalette(p); - setAutoFillBackground(true); - - setAlignment(Qt::AlignCenter); - - setAttribute(Qt::WA_TransparentForMouseEvents, true); + // record button + btn = new RecordButton(this); + vlayout->addWidget(btn, 0, Qt::AlignBottom | Qt::AlignRight); + QObject::connect(btn, &QPushButton::clicked, [=](bool checked) { + Params().putBool("EnableLogging", checked); + }); + w->raise(); QObject::connect(uiState(), &UIState::uiUpdate, this, &BodyWindow::updateState); } void BodyWindow::paintEvent(QPaintEvent *event) { - QLabel::paintEvent(event); + //QLabel::paintEvent(event); QPainter p(this); p.setRenderHint(QPainter::Antialiasing); - p.translate(width() - 136, 16); + p.fillRect(rect(), QColor(0, 0, 0)); // battery outline + detail + p.translate(width() - 136, 16); const QColor gray = QColor("#737373"); p.setBrush(Qt::NoBrush); p.setPen(QPen(gray, 4, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin)); @@ -79,9 +127,9 @@ void BodyWindow::updateState(const UIState &s) { // TODO: use carState.standstill when that's fixed const bool standstill = std::abs(cs.getVEgo()) < 0.01; QMovie *m = standstill ? sleep : awake; - if (m != movie()) { - setMovie(m); - movie()->start(); + if (m != face->movie()) { + face->setMovie(m); + face->movie()->start(); } update(); diff --git a/selfdrive/ui/qt/body.h b/selfdrive/ui/qt/body.h index cf1ffa191f..b49192a2bf 100644 --- a/selfdrive/ui/qt/body.h +++ b/selfdrive/ui/qt/body.h @@ -2,11 +2,22 @@ #include #include +#include #include "selfdrive/common/util.h" #include "selfdrive/ui/ui.h" -class BodyWindow : public QLabel { +class RecordButton : public QPushButton { + Q_OBJECT + +public: + RecordButton(QWidget* parent = 0); + +private: + void paintEvent(QPaintEvent*) override; +}; + +class BodyWindow : public QWidget { Q_OBJECT public: @@ -15,7 +26,9 @@ public: private: bool charging = false; FirstOrderFilter fuel_filter; + QLabel *face; QMovie *awake, *sleep; + RecordButton *btn; void paintEvent(QPaintEvent*) override; private slots: From 9307fe434cf7e9adb68a12d0b9073ebcf75e1f3e Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 4 May 2022 11:37:31 +0200 Subject: [PATCH 027/391] map.cc: fix crash on older route with missing liveLocationKalman values --- selfdrive/ui/qt/maps/map.cc | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index 3b8668d0b7..055f93b291 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -117,17 +117,15 @@ void MapWindow::timerUpdate() { auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman(); auto pos = location.getPositionGeodetic(); auto orientation = location.getCalibratedOrientationNED(); + auto velocity = location.getVelocityCalibrated(); - localizer_valid = (location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && pos.getValid(); + localizer_valid = (location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && + pos.getValid() && orientation.getValid() && velocity.getValid(); if (localizer_valid) { - float velocity = location.getVelocityCalibrated().getValue()[0]; - float bearing = RAD2DEG(orientation.getValue()[2]); - auto coordinate = QMapbox::Coordinate(pos.getValue()[0], pos.getValue()[1]); - - last_position = coordinate; - last_bearing = bearing; - velocity_filter.update(velocity); + last_position = QMapbox::Coordinate(pos.getValue()[0], pos.getValue()[1]); + last_bearing = RAD2DEG(orientation.getValue()[2]); + velocity_filter.update(velocity.getValue()[0]); } } From 3fc01ec15acc5a4f8fdd427240dfc178362760dd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 4 May 2022 11:44:16 +0200 Subject: [PATCH 028/391] cameraview.cc: set alignment to 1 when copying texture (#24418) --- selfdrive/ui/qt/widgets/cameraview.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index cb978182db..9d2d301ca8 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -216,6 +216,7 @@ void CameraViewWidget::paintGL() { if (latest_frame == nullptr) return; + glPixelStorei(GL_UNPACK_ALIGNMENT, 1); glViewport(0, 0, width(), height()); glBindVertexArray(frame_vao); @@ -238,6 +239,7 @@ void CameraViewWidget::paintGL() { glBindVertexArray(0); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); } void CameraViewWidget::vipcConnected(VisionIpcClient *vipc_client) { From e8892481abc7e3c529be35dd093614c50e6bfbbd Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Wed, 4 May 2022 12:12:13 +0200 Subject: [PATCH 029/391] ui: fix HUD drawing order (#24419) --- selfdrive/ui/qt/onroad.cc | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index cee347daa9..098747946f 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -294,6 +294,8 @@ void NvgWindow::updateFrameMat(int w, int h) { } void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { + painter.save(); + const UIScene &scene = s->scene; // lanelines for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { @@ -329,9 +331,13 @@ void NvgWindow::drawLaneLines(QPainter &painter, const UIState *s) { } painter.setBrush(bg); painter.drawPolygon(scene.track_vertices.v, scene.track_vertices.cnt); + + painter.restore(); } void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV3::Reader &lead_data, const QPointF &vd) { + painter.save(); + const float speedBuff = 10.; const float leadBuff = 40.; const float d_rel = lead_data.getX()[0]; @@ -361,6 +367,8 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; painter.setBrush(redColor(fillAlpha)); painter.drawPolygon(chevron, std::size(chevron)); + + painter.restore(); } void NvgWindow::paintGL() { @@ -370,8 +378,6 @@ void NvgWindow::paintGL() { painter.setRenderHint(QPainter::Antialiasing); painter.setPen(Qt::NoPen); - drawHud(painter); - UIState *s = uiState(); if (s->worldObjectsVisible()) { @@ -388,6 +394,8 @@ void NvgWindow::paintGL() { } } + drawHud(painter); + double cur_draw_t = millis_since_boot(); double dt = cur_draw_t - prev_draw_t; double fps = fps_filter.update(1. / dt * 1000); From 43d2a3c187368a7c6ddf40c03766f7a3a95dfb24 Mon Sep 17 00:00:00 2001 From: Lukas Petersson Date: Wed, 4 May 2022 14:05:41 -0700 Subject: [PATCH 030/391] warning instead assert (#24424) * warning instead assert * warning description --- tools/latencylogger/latency_logger.py | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/tools/latencylogger/latency_logger.py b/tools/latencylogger/latency_logger.py index b03dc84f61..319e73a769 100644 --- a/tools/latencylogger/latency_logger.py +++ b/tools/latencylogger/latency_logger.py @@ -83,8 +83,10 @@ def read_logs(lr): if msg_obj.frameIdExtra != frame_id: frame_mismatches.append(frame_id) - assert frame_id_fails < 20, "Too many frameId fetch fails" - assert len(frame_mismatches) < 20, "Too many frame mismatches" + if frame_id_fails > 20: + print("Warning, many frameId fetch fails", frame_id_fails) + if len(frame_mismatches) > 20: + print("Warning, many frame mismatches", len(frame_mismatches)) return (data, frame_mismatches) def find_frame_id(time, service, start_times, end_times): @@ -98,12 +100,11 @@ def find_t0(start_times, frame_id=-1): m = max(start_times.keys()) while frame_id <= m: for service in SERVICES: - if service in start_times[frame_id]: + if start_times[frame_id][service]: return start_times[frame_id][service] frame_id += 1 raise Exception('No start time has been set') - ## ASSUMES THAT AT LEAST ONE CLOUDLOG IS MADE IN CONTROLSD def insert_cloudlogs(lr, timestamps, start_times, end_times): t0 = find_t0(start_times) @@ -138,8 +139,10 @@ def insert_cloudlogs(lr, timestamps, start_times, end_times): timestamps[frame_id][service].append((event, time)) else: failed_inserts += 1 - assert latest_controls_frameid > 0, "No timestamp in controlsd" - assert failed_inserts < len(timestamps), "Too many failed cloudlog inserts" + if latest_controls_frameid == 0: + print("Warning, no timestamp in controlsd. Implementation assumes that a timestamp is made in controlsd to bind boardd logs to frame ID. Please add such a timestamp.") + elif failed_inserts > len(timestamps): + print("Warning, many cloudlog inserts failed", failed_inserts) def print_timestamps(timestamps, durations, start_times, relative): t0 = find_t0(start_times) @@ -159,17 +162,15 @@ def print_timestamps(timestamps, durations, start_times, relative): def graph_timestamps(timestamps, start_times, end_times, relative): t0 = find_t0(start_times) - y0 = min(start_times.keys()) fig, ax = plt.subplots() ax.set_xlim(0, 150 if relative else 750) - ax.set_ylim(y0, y0+15) + ax.set_ylim(0, 15) ax.set_xlabel('milliseconds') - ax.set_ylabel('Frame ID') colors = ['blue', 'green', 'red', 'yellow', 'purple'] assert len(colors) == len(SERVICES), 'Each service needs a color' points = {"x": [], "y": [], "labels": []} - for frame_id, services in timestamps.items(): + for i, (frame_id, services) in enumerate(timestamps.items()): if relative: t0 = find_t0(start_times, frame_id) service_bars = [] @@ -180,9 +181,9 @@ def graph_timestamps(timestamps, start_times, end_times, relative): service_bars.append(((start-t0)/1e6,(end-start)/1e6)) for event in events: points['x'].append((event[1]-t0)/1e6) - points['y'].append(frame_id) + points['y'].append(i) points['labels'].append(event[0]) - ax.broken_barh(service_bars, (frame_id-0.45, 0.9), facecolors=(colors), alpha=0.5) + ax.broken_barh(service_bars, (i-0.45, 0.9), facecolors=(colors), alpha=0.5) scatter = ax.scatter(points['x'], points['y'], marker='d', edgecolor='black') tooltip = mpld3.plugins.PointLabelTooltip(scatter, labels=points['labels']) @@ -212,6 +213,7 @@ if __name__ == "__main__": r = DEMO_ROUTE if args.demo else args.route_or_segment_name.strip() lr = logreader_from_route_or_segment(r, sort_by_time=True) + data, _ = get_timestamps(lr) print_timestamps(data['timestamp'], data['duration'], data['start'], args.relative) if args.plot: From 930d0c01a90ba6a7b321516a276cc0e6e6862514 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 May 2022 14:16:27 -0700 Subject: [PATCH 031/391] latency logger: better errors and minor cleanup --- tools/latencylogger/latency_logger.py | 32 ++++++++++++++------------- 1 file changed, 17 insertions(+), 15 deletions(-) diff --git a/tools/latencylogger/latency_logger.py b/tools/latencylogger/latency_logger.py index 319e73a769..11ec4850ec 100644 --- a/tools/latencylogger/latency_logger.py +++ b/tools/latencylogger/latency_logger.py @@ -7,7 +7,7 @@ import sys from collections import defaultdict from tools.lib.logreader import logreader_from_route_or_segment - + DEMO_ROUTE = "9f583b1d93915c31|2022-04-26--18-49-49" SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd'] @@ -25,7 +25,7 @@ MSGQ_TO_SERVICE = { SERVICE_TO_DURATIONS = { 'camerad': ['processingTime'], 'modeld': ['modelExecutionTime', 'gpuExecutionTime'], - 'plannerd': ["solverExecutionTime"], + 'plannerd': ['solverExecutionTime'], } def read_logs(lr): @@ -38,7 +38,7 @@ def read_logs(lr): if msg.which() == 'sendcan': latest_sendcan_monotime = msg.logMonoTime continue - + if msg.which() in MSGQ_TO_SERVICE: service = MSGQ_TO_SERVICE[msg.which()] msg_obj = getattr(msg, msg.which()) @@ -105,9 +105,10 @@ def find_t0(start_times, frame_id=-1): frame_id += 1 raise Exception('No start time has been set') -## ASSUMES THAT AT LEAST ONE CLOUDLOG IS MADE IN CONTROLSD def insert_cloudlogs(lr, timestamps, start_times, end_times): - t0 = find_t0(start_times) + # at least one cloudlog must be made in controlsd + + t0 = find_t0(start_times) failed_inserts = 0 latest_controls_frameid = 0 for msg in lr: @@ -118,7 +119,7 @@ def insert_cloudlogs(lr, timestamps, start_times, end_times): service = jmsg['ctx']['daemon'] event = jmsg['msg']['timestamp']['event'] if time < t0: - # Filter out controlsd messages which arrive before the camera loop + # Filter out controlsd messages which arrive before the camera loop continue if "frame_id" in jmsg['msg']['timestamp']: @@ -139,29 +140,30 @@ def insert_cloudlogs(lr, timestamps, start_times, end_times): timestamps[frame_id][service].append((event, time)) else: failed_inserts += 1 + if latest_controls_frameid == 0: - print("Warning, no timestamp in controlsd. Implementation assumes that a timestamp is made in controlsd to bind boardd logs to frame ID. Please add such a timestamp.") + print("Warning: failed to bind boardd logs to a frame ID. Add a timestamp cloudlog in controlsd.") elif failed_inserts > len(timestamps): - print("Warning, many cloudlog inserts failed", failed_inserts) + print(f"Warning: failed to bind {failed_inserts} cloudlog timestamps to a frame ID") def print_timestamps(timestamps, durations, start_times, relative): - t0 = find_t0(start_times) + t0 = find_t0(start_times) for frame_id in timestamps.keys(): print('='*80) print("Frame ID:", frame_id) if relative: - t0 = find_t0(start_times, frame_id) + t0 = find_t0(start_times, frame_id) for service in SERVICES: - print(" "+service) + print(" "+service) events = timestamps[frame_id][service] for event, time in sorted(events, key = lambda x: x[1]): - print(" "+'%-53s%-53s' %(event, str((time-t0)/1e6))) + print(" "+'%-53s%-53s' %(event, str((time-t0)/1e6))) for event, time in durations[frame_id][service]: - print(" "+'%-53s%-53s' %(event, str(time*1000))) + print(" "+'%-53s%-53s' %(event, str(time*1000))) def graph_timestamps(timestamps, start_times, end_times, relative): - t0 = find_t0(start_times) + t0 = find_t0(start_times) fig, ax = plt.subplots() ax.set_xlim(0, 150 if relative else 750) ax.set_ylim(0, 15) @@ -172,7 +174,7 @@ def graph_timestamps(timestamps, start_times, end_times, relative): points = {"x": [], "y": [], "labels": []} for i, (frame_id, services) in enumerate(timestamps.items()): if relative: - t0 = find_t0(start_times, frame_id) + t0 = find_t0(start_times, frame_id) service_bars = [] for service, events in services.items(): if start_times[frame_id][service] and end_times[frame_id][service]: From 2466233b1cf5195bc4005c647d00408c838fe1a8 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 May 2022 14:57:39 -0700 Subject: [PATCH 032/391] body: opt-out logging (#24423) * body: opt-out logging * wait a bit * little better * fix that too Co-authored-by: Comma Device --- selfdrive/common/params.cc | 2 +- selfdrive/manager/process_config.py | 2 +- selfdrive/ui/qt/body.cc | 33 +++++++++++++++++++++++++---- selfdrive/ui/qt/body.h | 2 ++ selfdrive/ui/qt/home.cc | 2 +- selfdrive/ui/ui.cc | 2 +- 6 files changed, 35 insertions(+), 8 deletions(-) diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index 9cc7a113cb..c294c48dfe 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -94,6 +94,7 @@ std::unordered_map keys = { {"CompletedTrainingVersion", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, + {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, {"DisableRadar_Allow", PERSISTENT}, {"DisableRadar", PERSISTENT}, // WARNING: THIS DISABLES AEB @@ -103,7 +104,6 @@ std::unordered_map keys = { {"DoReboot", CLEAR_ON_MANAGER_START}, {"DoShutdown", CLEAR_ON_MANAGER_START}, {"DoUninstall", CLEAR_ON_MANAGER_START}, - {"EnableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"EnableWideCamera", CLEAR_ON_MANAGER_START}, {"EndToEndToggle", PERSISTENT}, {"ForcePowerDown", CLEAR_ON_MANAGER_START}, diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 34b120efaf..8fa0454011 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -14,7 +14,7 @@ def notcar(started: bool, params: Params, CP: car.CarParams) -> bool: return CP.notCar def logging(started, params, CP: car.CarParams) -> bool: - run = (not CP.notCar) or params.get_bool("EnableLogging") + run = (not CP.notCar) or not params.get_bool("DisableLogging") return started and run procs = [ diff --git a/selfdrive/ui/qt/body.cc b/selfdrive/ui/qt/body.cc index 01b91571a4..7ca064a6cf 100644 --- a/selfdrive/ui/qt/body.cc +++ b/selfdrive/ui/qt/body.cc @@ -7,11 +7,16 @@ #include #include "selfdrive/common/params.h" +#include "selfdrive/common/timing.h" RecordButton::RecordButton(QWidget *parent) : QPushButton(parent) { setCheckable(true); setChecked(false); setFixedSize(148, 148); + + QObject::connect(this, &QPushButton::toggled, [=]() { + setEnabled(false); + }); } void RecordButton::paintEvent(QPaintEvent *event) { @@ -20,8 +25,13 @@ void RecordButton::paintEvent(QPaintEvent *event) { QPoint center(width() / 2, height() / 2); - QColor bg(isChecked() ? "#FFFFFF" : "#404040"); + QColor bg(isChecked() ? "#FFFFFF" : "#737373"); QColor accent(isChecked() ? "#FF0000" : "#FFFFFF"); + if (!isEnabled()) { + bg = QColor("#404040"); + accent = QColor("#FFFFFF"); + } + if (isDown()) { accent.setAlphaF(0.7); } @@ -62,7 +72,9 @@ BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QW btn = new RecordButton(this); vlayout->addWidget(btn, 0, Qt::AlignBottom | Qt::AlignRight); QObject::connect(btn, &QPushButton::clicked, [=](bool checked) { - Params().putBool("EnableLogging", checked); + btn->setEnabled(false); + Params().putBool("DisableLogging", !checked); + last_button = nanos_since_boot(); }); w->raise(); @@ -70,8 +82,6 @@ BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QW } void BodyWindow::paintEvent(QPaintEvent *event) { - //QLabel::paintEvent(event); - QPainter p(this); p.setRenderHint(QPainter::Antialiasing); @@ -112,6 +122,11 @@ void BodyWindow::paintEvent(QPaintEvent *event) { } } +void BodyWindow::offroadTransition(bool offroad) { + btn->setChecked(true); + btn->setEnabled(true); + fuel_filter.reset(1.0); +} void BodyWindow::updateState(const UIState &s) { if (!isVisible()) { @@ -132,5 +147,15 @@ void BodyWindow::updateState(const UIState &s) { face->movie()->start(); } + // update record button state + if (sm.updated("managerState") && (sm.rcv_time("managerState") - last_button)*1e-9 > 0.5) { + for (auto proc : sm["managerState"].getManagerState().getProcesses()) { + if (proc.getName() == "loggerd") { + btn->setEnabled(true); + btn->setChecked(proc.getRunning()); + } + } + } + update(); } diff --git a/selfdrive/ui/qt/body.h b/selfdrive/ui/qt/body.h index b49192a2bf..6555487bf1 100644 --- a/selfdrive/ui/qt/body.h +++ b/selfdrive/ui/qt/body.h @@ -25,6 +25,7 @@ public: private: bool charging = false; + uint64_t last_button = 0; FirstOrderFilter fuel_filter; QLabel *face; QMovie *awake, *sleep; @@ -33,4 +34,5 @@ private: private slots: void updateState(const UIState &s); + void offroadTransition(bool onroad); }; diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 0b64900770..fbd458cc02 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -32,7 +32,6 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { body = new BodyWindow(this); slayout->addWidget(body); - body->setEnabled(false); driver_view = new DriverViewWindow(this); connect(driver_view, &DriverViewWindow::done, [=] { @@ -59,6 +58,7 @@ void HomeWindow::updateState(const UIState &s) { } void HomeWindow::offroadTransition(bool offroad) { + body->setEnabled(false); sidebar->setVisible(offroad); if (offroad) { slayout->setCurrentWidget(home); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 0debb5ba04..ab99b8fc24 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -233,7 +233,7 @@ UIState::UIState(QObject *parent) : QObject(parent) { sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", "pandaStates", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", - "wideRoadCameraState", + "wideRoadCameraState", "managerState", }); Params params; From e3fd6a7c5074d5f06edf4738f46347844a5cef4f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 4 May 2022 15:00:47 -0700 Subject: [PATCH 033/391] Add azure-storage-blob to dev packages (#24426) * add azure-storage-blob * same --- Pipfile | 1 + Pipfile.lock | 24 +++++++++++++++++++++++- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/Pipfile b/Pipfile index 6d30179b9d..473b873077 100644 --- a/Pipfile +++ b/Pipfile @@ -4,6 +4,7 @@ url = "https://pypi.org/simple" verify_ssl = true [dev-packages] +azure-storage-blob = "~=2.1" control = "*" coverage = "*" dictdiffer = "*" diff --git a/Pipfile.lock b/Pipfile.lock index 2c62e13dfa..4398c37d29 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "41e285b10b9b5a353b3eb9c202886e52d22403c369784877aaa35e099aa203a8" + "sha256": "918c8cba5c6a0242dc0f6ea74246176a1c54f0a9395feddf35af2189cc813378" }, "pipfile-spec": 6, "requires": { @@ -1111,6 +1111,28 @@ "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", "version": "==21.4.0" }, + "azure-common": { + "hashes": [ + "sha256:4ac0cd3214e36b6a1b6a442686722a5d8cc449603aa833f3f0f40bda836704a3", + "sha256:5c12d3dcf4ec20599ca6b0d3e09e86e146353d443e7fcc050c9a19c1f9df20ad" + ], + "version": "==1.1.28" + }, + "azure-storage-blob": { + "hashes": [ + "sha256:a8e91a51d4f62d11127c7fd8ba0077385c5b11022f0269f8a2a71b9fc36bef31", + "sha256:b90323aad60f207f9f90a0c4cf94c10acc313c20b39403398dfba51f25f7b454" + ], + "index": "pypi", + "version": "==2.1.0" + }, + "azure-storage-common": { + "hashes": [ + "sha256:b01a491a18839b9d05a4fe3421458a0ddb5ab9443c14e487f40d16f9a1dc2fbe", + "sha256:ccedef5c67227bc4d6670ffd37cec18fb529a1b7c3a5e53e4096eb0cf23dc73f" + ], + "version": "==2.1.0" + }, "babel": { "hashes": [ "sha256:ab49e12b91d937cd11f0b67cb259a57ab4ad2b59ac7a3b41d6c06c0ac5b0def9", From 674a2061fd9f0213b14851d82832cff6d684d12f Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 May 2022 15:08:08 -0700 Subject: [PATCH 034/391] CI: allow triggering prebuilt workflow manually --- .github/workflows/prebuilt.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/prebuilt.yaml b/.github/workflows/prebuilt.yaml index 80942b3bc5..807ac06b94 100644 --- a/.github/workflows/prebuilt.yaml +++ b/.github/workflows/prebuilt.yaml @@ -3,6 +3,8 @@ on: schedule: - cron: '0 * * * *' + workflow_dispatch: + env: BASE_IMAGE: openpilot-base DOCKER_REGISTRY: ghcr.io/commaai From 1bc6f2fa7db49ebd3d29063e2a93234488b88db0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 4 May 2022 15:58:08 -0700 Subject: [PATCH 035/391] increase cruiseMismatch threshold (#24428) --- selfdrive/controls/controlsd.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 6dff3bb2e1..498218ab46 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -343,7 +343,7 @@ class Controls: # Check for mismatch between openpilot and car's PCM cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 - if self.cruise_mismatch_counter > int(3. / DT_CTRL): + if self.cruise_mismatch_counter > int(6. / DT_CTRL): self.events.add(EventName.cruiseMismatch) # Check for FCW From 1f9907122a9bda9279d73f698addaa0e22796059 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 13:06:13 +0200 Subject: [PATCH 036/391] make debayering consistent at edges (#24437) --- selfdrive/camerad/cameras/real_debayer.cl | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 6452e44ebb..8cb0aeb166 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -104,38 +104,38 @@ __kernel void debayer10(const __global uchar * in, half pv = val_from_10(in, x_global, y_global, black_level); cached[localOffset] = pv; - // don't care - if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { - return; - } - // cache padding int localColOffset = -1; int globalColOffset = -1; // cache padding - if (x_local < 1) { + if (x_global >= 1 && x_local < 1) { localColOffset = x_local; globalColOffset = -1; cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-1, y_global, black_level); - } else if (x_local >= get_local_size(0) - 1) { + } else if (x_global < RGB_WIDTH - 1 && x_local >= get_local_size(0) - 1) { localColOffset = x_local + 2; globalColOffset = 1; cached[localOffset + 1] = val_from_10(in, x_global+1, y_global, black_level); } - if (y_local < 1) { + if (y_global >= 1 && y_local < 1) { cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-1, black_level); if (localColOffset != -1) { cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global-1, black_level); } - } else if (y_local >= get_local_size(1) - 1) { + } else if (y_global < RGB_HEIGHT - 1 && y_local >= get_local_size(1) - 1) { cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+1, black_level); if (localColOffset != -1) { cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global+1, black_level); } } + // don't care + if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { + return; + } + // sync barrier(CLK_LOCAL_MEM_FENCE); From 9da9b773eba344e9e59aeaa8a2c0235aadbd1f44 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 16:05:37 +0200 Subject: [PATCH 037/391] test for comparing debayer results to ref commit (#24420) * test for comparing debayering results to ref commit * fix run on device * print more useful diff * limit to diff output * remove env var * ref * more useful diff * use real local work size * remove pyopencl install * update ref * include rgb_to_yuv * fix diff * get kernel build out of loop Co-authored-by: Comma Device --- .../process_replay/debayer_replay_ref_commit | 1 + selfdrive/test/process_replay/test_debayer.py | 205 ++++++++++++++++++ 2 files changed, 206 insertions(+) create mode 100644 selfdrive/test/process_replay/debayer_replay_ref_commit create mode 100755 selfdrive/test/process_replay/test_debayer.py diff --git a/selfdrive/test/process_replay/debayer_replay_ref_commit b/selfdrive/test/process_replay/debayer_replay_ref_commit new file mode 100644 index 0000000000..44fe33001c --- /dev/null +++ b/selfdrive/test/process_replay/debayer_replay_ref_commit @@ -0,0 +1 @@ +1f9907122a9bda9279d73f698addaa0e22796059 \ No newline at end of file diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py new file mode 100755 index 0000000000..17fa9afd63 --- /dev/null +++ b/selfdrive/test/process_replay/test_debayer.py @@ -0,0 +1,205 @@ +#!/usr/bin/env python3 +import os +import sys +import bz2 +import numpy as np + +import pyopencl as cl # install with `PYOPENCL_CL_PRETEND_VERSION=2.0 pip install pyopencl` + +from selfdrive.hardware import PC, TICI +from common.basedir import BASEDIR +from selfdrive.test.openpilotci import BASE_URL, get_url +from selfdrive.version import get_commit +from tools.lib.logreader import LogReader +from tools.lib.filereader import FileReader + +TEST_ROUTE = "8345e3b82948d454|2022-05-04--13-45-33" +SEGMENT = 0 + +FRAME_WIDTH = 1928 +FRAME_HEIGHT = 1208 +FRAME_STRIDE = 2896 + +UV_WIDTH = FRAME_WIDTH // 2 +UV_HEIGHT = FRAME_HEIGHT // 2 +UV_SIZE = UV_WIDTH * UV_HEIGHT + +def get_frame_fn(ref_commit, test_route, tici=True): + return f"{test_route}_debayer{'_tici' if tici else ''}_{ref_commit}.bz2" + +def bzip_frames(frames): + data = bytes() + for y, u, v in frames: + data += y.tobytes() + data += u.tobytes() + data += v.tobytes() + return bz2.compress(data) + +def unbzip_frames(url): + with FileReader(url) as f: + dat = f.read() + + data = bz2.decompress(dat) + + res = [] + for y_start in range(0, len(data), FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2): + u_start = y_start + FRAME_WIDTH * FRAME_HEIGHT + v_start = u_start + UV_SIZE + + y = np.frombuffer(data[y_start: u_start], dtype=np.uint8).reshape((FRAME_HEIGHT, FRAME_WIDTH)) + u = np.frombuffer(data[u_start: v_start], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) + v = np.frombuffer(data[v_start: v_start + UV_SIZE], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) + + res.append((y, u, v)) + + return res + +def init_kernels(): + ctx = cl.create_some_context() + + with open(os.path.join(BASEDIR, 'selfdrive/camerad/cameras/real_debayer.cl')) as f: + build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ + f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DCAM_NUM=0' + if PC: + build_args += ' -DHALF_AS_FLOAT=1' + debayer_prg = cl.Program(ctx, f.read()).build(options=build_args) + + with open(os.path.join(BASEDIR, 'selfdrive/camerad/transforms/rgb_to_yuv.cl')) as f: + build_args = f' -cl-fast-relaxed-math -cl-denorms-are-zero -DWIDTH={FRAME_WIDTH} -DHEIGHT={FRAME_HEIGHT}' + \ + f' -DUV_WIDTH={UV_WIDTH} -DUV_HEIGHT={UV_HEIGHT} -DRGB_STRIDE={FRAME_WIDTH*3}' + \ + f' -DRGB_SIZE={FRAME_WIDTH*FRAME_HEIGHT}' + rgb_to_yuv_prg = cl.Program(ctx, f.read()).build(options=build_args) + + return ctx, debayer_prg, rgb_to_yuv_prg + +def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): + q = cl.CommandQueue(ctx) + + rgb_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT * 3, dtype=np.uint8) + yuv_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2, dtype=np.uint8) + + cam_g = cl.Buffer(ctx, cl.mem_flags.READ_ONLY | cl.mem_flags.COPY_HOST_PTR, hostbuf=data) + rgb_wg = cl.Buffer(ctx, cl.mem_flags.WRITE_ONLY, FRAME_WIDTH * FRAME_HEIGHT * 3) + yuv_g = cl.Buffer(ctx, cl.mem_flags.WRITE_ONLY, FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2) + + local_worksize = (16, 16) if TICI else (8, 8) + local_mem = cl.LocalMemory(648 if TICI else 400) + ev1 = debayer_prg.debayer10(q, (FRAME_WIDTH, FRAME_HEIGHT), local_worksize, cam_g, rgb_wg, local_mem, np.float32(42)) + cl.enqueue_copy(q, rgb_buff, rgb_wg, wait_for=[ev1]).wait() + cl.enqueue_barrier(q) + + rgb_rg = cl.Buffer(ctx, cl.mem_flags.READ_ONLY | cl.mem_flags.COPY_HOST_PTR, hostbuf=rgb_buff) + cl.enqueue_barrier(q) + + ev3 = rgb_to_yuv_prg.rgb_to_yuv(q, (FRAME_WIDTH // 4, FRAME_HEIGHT // 4), None, rgb_rg, yuv_g) + cl.enqueue_barrier(q) + + cl.enqueue_copy(q, yuv_buff, yuv_g, wait_for=[ev3]).wait() + cl.enqueue_barrier(q) + + y = yuv_buff[:FRAME_WIDTH*FRAME_HEIGHT].reshape((FRAME_HEIGHT, FRAME_WIDTH)) + u = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT:FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE].reshape((UV_HEIGHT, UV_WIDTH)) + v = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE:].reshape((UV_HEIGHT, UV_WIDTH)) + + return y, u, v + +def debayer_replay(lr): + ctx, debayer_prg, rgb_to_yuv_prg = init_kernels() + + frames = [] + for m in lr: + if m.which() == 'roadCameraState': + cs = m.roadCameraState + if cs.image: + data = np.frombuffer(cs.image, dtype=np.uint8) + img = debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data) + + frames.append(img) + + return frames + +if __name__ == "__main__": + update = "--update" in sys.argv + replay_dir = os.path.dirname(os.path.abspath(__file__)) + ref_commit_fn = os.path.join(replay_dir, "debayer_replay_ref_commit") + + # load logs + lr = list(LogReader(get_url(TEST_ROUTE, SEGMENT))) + + # run replay + frames = debayer_replay(lr) + + # get diff + failed = False + diff = '' + yuv_i = ['y', 'u', 'v'] + if not update: + with open(ref_commit_fn) as f: + ref_commit = f.read().strip() + frame_fn = get_frame_fn(ref_commit, TEST_ROUTE, tici=TICI) + + try: + cmp_frames = unbzip_frames(BASE_URL + frame_fn) + + if len(frames) != len(cmp_frames): + failed = True + diff += 'amount of frames not equal\n' + + for i, (frame, cmp_frame) in enumerate(zip(frames, cmp_frames)): + for j in range(3): + fr = frame[j] + cmp_f = cmp_frame[j] + if fr.shape != cmp_f.shape: + failed = True + diff += f'frame shapes not equal for ({i}, {yuv_i[j]})\n' + diff += f'{ref_commit}: {cmp_f.shape}\n' + diff += f'HEAD: {fr.shape}\n' + elif not np.array_equal(fr, cmp_f): + failed = True + if np.allclose(fr, cmp_f, atol=1): + diff += f'frames not equal for ({i}, {yuv_i[j]}), but are all close\n' + else: + diff += f'frames not equal for ({i}, {yuv_i[j]})\n' + + frame_diff = np.abs(np.subtract(fr, cmp_f)) + diff_len = len(np.nonzero(frame_diff)[0]) + if diff_len > 1000: + diff += f'different at a large amount of pixels ({diff_len})\n' + else: + diff += 'different at (frame, yuv, pixel, ref, HEAD):\n' + for k in zip(*np.nonzero(frame_diff)): + diff += f'{i}, {yuv_i[j]}, {k}, {cmp_f[k]}, {fr[k]}\n' + + if failed: + print(diff) + with open("debayer_diff.txt", "w") as f: + f.write(diff) + except Exception as e: + print(str(e)) + failed = True + + # upload new refs + if update or failed: + from selfdrive.test.openpilotci import upload_file + + print("Uploading new refs") + + frames_bzip = bzip_frames(frames) + + new_commit = get_commit() + frame_fn = os.path.join(replay_dir, get_frame_fn(new_commit, TEST_ROUTE, tici=TICI)) + with open(frame_fn, "wb") as f2: + f2.write(frames_bzip) + + try: + upload_file(frame_fn, os.path.basename(frame_fn)) + except Exception as e: + print("failed to upload", e) + + if update: + with open(ref_commit_fn, 'w') as f: + f.write(str(new_commit)) + + print("\nNew ref commit: ", new_commit) + + sys.exit(int(failed)) From d8c0cf5d55890cc46aff51f1fe1345e339863000 Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Thu, 5 May 2022 17:38:39 +0200 Subject: [PATCH 038/391] debayering: typedef half as float to run on pc (#24439) * debayering: typedef half as float to run on pc * add casts to literals * define existing half type * remove test code --- selfdrive/camerad/cameras/real_debayer.cl | 31 +++++++++++++---------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 8cb0aeb166..50a7846213 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -1,11 +1,14 @@ +#ifdef HALF_AS_FLOAT +#define half float +#define half3 float3 +#else #pragma OPENCL EXTENSION cl_khr_fp16 : enable +#endif -const __constant half3 color_correction[3] = { - // post wb CCM - (half3)(1.82717181, -0.31231438, 0.07307673), - (half3)(-0.5743977, 1.36858544, -0.53183455), - (half3)(-0.25277411, -0.05627105, 1.45875782), -}; +// post wb CCM +const __constant half3 color_correction_0 = (half3)(1.82717181, -0.31231438, 0.07307673); +const __constant half3 color_correction_1 = (half3)(-0.5743977, 1.36858544, -0.53183455); +const __constant half3 color_correction_2 = (half3)(-0.25277411, -0.05627105, 1.45875782); // tone mapping params const half cpk = 0.75; @@ -25,15 +28,15 @@ half mf(half x, half cp) { } half3 color_correct(half3 rgb) { - half3 ret = (0,0,0); + half3 ret = (half3)(0.0, 0.0, 0.0); half cpx = 0.01; - ret += (half)rgb.x * color_correction[0]; - ret += (half)rgb.y * color_correction[1]; - ret += (half)rgb.z * color_correction[2]; + ret += (half)rgb.x * color_correction_0; + ret += (half)rgb.y * color_correction_1; + ret += (half)rgb.z * color_correction_2; ret.x = mf(ret.x, cpx); ret.y = mf(ret.y, cpx); ret.z = mf(ret.z, cpx); - ret = clamp(0.0h, 255.0h, ret*255.0h); + ret = clamp(0.0, 255.0, ret*255.0); return ret; } @@ -46,7 +49,7 @@ inline half val_from_10(const uchar * source, int gx, int gy, half black_level) half pv = (half)((major + minor)/4); // normalize - pv = max(0.0h, pv - black_level); + pv = max((half)0.0, pv - black_level); pv /= (1024.0f - black_level); // correct vignetting @@ -67,7 +70,7 @@ inline half val_from_10(const uchar * source, int gx, int gy, half black_level) pv = s * pv; } - pv = clamp(0.0h, 1.0h, pv); + pv = clamp((half)0.0, (half)1.0, pv); return pv; } @@ -197,7 +200,7 @@ __kernel void debayer10(const __global uchar * in, } } - rgb = clamp(0.0h, 1.0h, rgb); + rgb = clamp(0.0, 1.0, rgb); rgb = color_correct(rgb); out[out_idx + 0] = (uchar)(rgb.z); From 6efb42613b79d53dbe4f802e1d6357953c6253d1 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 5 May 2022 10:21:46 -0700 Subject: [PATCH 039/391] Toyota: Add missing FW versions for RAV4 Hybrid 2022 (#24430) --- selfdrive/car/toyota/values.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 2d9948b9ab..0fa83d56cc 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1337,6 +1337,7 @@ FW_VERSIONS = { b'\x01F15264283100\x00\x00\x00\x00', b'\x01F15264286200\x00\x00\x00\x00', b'\x01F15264286100\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', @@ -1347,6 +1348,7 @@ FW_VERSIONS = { b'\x01896634A62000\x00\x00\x00\x00', b'\x01896634A08000\x00\x00\x00\x00', b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A02001\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R01100\x00\x00\x00\x00', From da74085d561198af0d06422df1758222edcc6d64 Mon Sep 17 00:00:00 2001 From: Brandon Zimmerman Date: Thu, 5 May 2022 13:20:53 -0500 Subject: [PATCH 040/391] Toyota: add missing FW versions for 2022 Lexus ES 300h (#24431) * Add 2022 Lexus ES Hybrid f/w - LEXUS_ESH_TSS2 2022 Lexus ES Hybrid * change carinfo Co-authored-by: Shane Smiskol --- docs/CARS.md | 2 +- selfdrive/car/toyota/values.py | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 14664d480c..8a78afe5cb 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -47,7 +47,7 @@ How We Rate The Cars |Kia|Niro Electric 2019-22|All|||||| |Kia|Telluride 2020|SCC + LKAS|||||| |Lexus|ES 2019-21|All|||||| -|Lexus|ES Hybrid 2019-21|All|||||| +|Lexus|ES Hybrid 2019-22|All|||||| |Lexus|NX 2020|All|||||| |Lexus|RX 2020-22|All|||||| |Lexus|RX Hybrid 2020-21|All|||||| diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0fa83d56cc..0ad2a419cf 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -151,7 +151,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { CAR.LEXUS_CTH: ToyotaCarInfo("Lexus CT Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ESH: ToyotaCarInfo("Lexus ES Hybrid 2017-18", "LSS", footnotes=[Footnote.DSU]), CAR.LEXUS_ES_TSS2: ToyotaCarInfo("Lexus ES 2019-21"), - CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-21"), + CAR.LEXUS_ESH_TSS2: ToyotaCarInfo("Lexus ES Hybrid 2019-22"), CAR.LEXUS_IS: ToyotaCarInfo("Lexus IS 2017-19"), CAR.LEXUS_NX: ToyotaCarInfo("Lexus NX 2018-19", footnotes=[Footnote.DSU]), CAR.LEXUS_NXH: ToyotaCarInfo("Lexus NX Hybrid 2018-19", footnotes=[Footnote.DSU]), @@ -1450,22 +1450,26 @@ FW_VERSIONS = { b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + b'\x01896633T38000\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ b'F152633423\x00\x00\x00\x00\x00\x00', b'F152633680\x00\x00\x00\x00\x00\x00', b'F152633681\x00\x00\x00\x00\x00\x00', + b'F152633F50\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B33252\x00\x00\x00\x00\x00\x00', b'8965B33590\x00\x00\x00\x00\x00\x00', b'8965B33690\x00\x00\x00\x00\x00\x00', + b'8965B33721\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', b'\x018821F3301200\x00\x00\x00\x00', b'\x018821F3301300\x00\x00\x00\x00', b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', @@ -1474,6 +1478,7 @@ FW_VERSIONS = { b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', ], }, CAR.LEXUS_ESH: { From 4beb764aed74cfda7b873d87bb82f3a5117df3e8 Mon Sep 17 00:00:00 2001 From: Left5566 Date: Fri, 6 May 2022 02:59:15 +0800 Subject: [PATCH 041/391] Toyota: add missing Prius TSS2 engine FW (#24438) Prius 2021 DongleID/route c3834a2fe82b632b|2022-05-05--19-39-41 --- selfdrive/car/toyota/values.py | 1 + 1 file changed, 1 insertion(+) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0ad2a419cf..e3cb0b091b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1765,6 +1765,7 @@ FW_VERSIONS = { CAR.PRIUS_TSS2: { (Ecu.engine, 0x700, None): [ b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', From 66fbce638f1a6a2bc9c08c4a17d5efe47fb91651 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 5 May 2022 19:13:06 -0700 Subject: [PATCH 042/391] uploader: compress rlogs (#24447) --- selfdrive/loggerd/uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index d13026c4b3..50557fffaa 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -261,7 +261,7 @@ def uploader_fn(exit_event): key, fn = d # qlogs and bootlogs need to be compressed before uploading - if key.endswith('qlog') or (key.startswith('boot/') and not key.endswith('.bz2')): + if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): key += ".bz2" success = uploader.upload(key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) From b16e612102558c6b94a0c1b7127596dab6f5b2d0 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Thu, 5 May 2022 19:42:18 -0700 Subject: [PATCH 043/391] remove eon debug scripts --- scripts/clwaste | Bin 155368 -> 0 bytes scripts/restart_modem.sh | 2 - scripts/throttling.sh | 16 ----- scripts/waste | Bin 8608 -> 0 bytes selfdrive/debug/compare_fingerprints.py | 19 ----- .../debug/internal/core_voltage_sweep.py | 23 ------ .../debug/internal/sensor_test_bootloop.py | 67 ------------------ 7 files changed, 127 deletions(-) delete mode 100755 scripts/clwaste delete mode 100755 scripts/restart_modem.sh delete mode 100755 scripts/throttling.sh delete mode 100755 scripts/waste delete mode 100755 selfdrive/debug/compare_fingerprints.py delete mode 100755 selfdrive/debug/internal/core_voltage_sweep.py delete mode 100755 selfdrive/debug/internal/sensor_test_bootloop.py diff --git a/scripts/clwaste b/scripts/clwaste deleted file mode 100755 index 51770f0e372cbd3bc08867bc329c756aca237973..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 155368 zcmc$H34B!5_5Yh0mPy#j24TtOl0>Q`5J(WpBq2%wF_O4ct&<@H639jpHW3K~+hEW# zfJ@bu04|vkm0D5aQUcf(3vEfU=+7=DL2F{rf@~Qi&i{Mvy>I5un>Psb*Z*(wxq0uN zbI-Zwo_p@O%e(iz)mgJ{F&Yet`ZFnSDHPi|n?o!D(RjB}+$oAhNmb1FKT3&I`T*J+ z!6LBQYqMajUdx#!$dmus!B*#$}iAwR}W9AUKLgv{-0zGlwku$D$&6z zXU>PjBGeHfsP-By!qS`O7MI;rQe3vEuyVq9Le(Pt4q+KW6~eU$zeXrTs7IjR zUW9AdoubUd^+kkD2){sh51|yHAHq!t^vh@e6~&2b4Z^Pw)+5mG9)zDGyhRcG9zY-& zHXyu?unJ)@g7y~#zyO4I5SAlY5cVOwim(RZA%rCeLl8zIL?G-$n1L`5;WdQk5t0#B zBJ4)^EkYf_3kXjj#35`)xF6vSgeHU$2+tv8A>4-WG=ln@hntrX>!tfl>Hb#SPm$s=xbH8;)1`auZ5jZ12on*63s&yN z{TKx8Z;}9H;2JFMhvPa|+|y+$LNwjr_alS_2=^kyBGAvqFUmr3EywkCaZf&C5kfJ- zjRKY{uG&kI08GR61_^l`?(aaTkYGjP{!Ved57)^O{wKIELs*OOuz(lfdW*Opi>no( z0U-*3eyIqLBkZ6Ee!oQMh44d!6$teE8A2mMUy9&Yjqnt^QxpfT&mfc_j6+z8FdZQQ zAspdmggFR%5PpE5{vK3sE^#%XcA8b;rF14(>qgP9sNmngSYwesUNro{29D_jd??`K zU*z$Fg5Uz+F%lnYEA)#+;i)}ne{Z4idT@u4`$%p2;2@swx<-!47YU9*E3{iRNi%)c>EdxPk_VH<1;CM{I&q;Zx!-i6ne`O`ur2}(c_;4 z!Svwdi}m1P0rY&A$hU(UFMd1uMJW{JZJ5OcX%+Af`{?rz3ZUnb0D8!QJZjq(tl8y& z$hYnQhn^A0mjduVF49*}Cx&0B&|6#pJwF}*o(soBcKe~|MAZ5%1f1%k$}j%B0dqC+A*wBEzx(fp!}3XtzAq$mCC`UOw8PBh@B04F_kYufc5kzVVsq5{Zo zfp~iIe<0*+CdZ54a?sQ7xPU)RP9MJ${GxOP;L|%myZ#dV^y-)Td_8$41!(Wn2XOsp z{mk8flb-Jp?MU^{;{)iqM5MQD;RPDYt4(nTcg%xJ-$8>*{2JJQjI9Q7 z`}tVYj!pru$N$j)?JFC62Ez^;1Rud(xjlfKcOyNO_vwv1WwRhS7NA}h1@JS+1K2Z7 z8ujFVN#t8C1|DjCjS65_A2I#(Q}P}_LGXjwv)^L@?D-49|HP9#U7bk3IDj7V1Hh+X z@JISN*ufbz3qIw5Q+sdKwD(^G(8J?`&k13-p9y=&1V3H?`uzdyZL3*d&%FcK z`E}q=?I=1}WGMLG7yv#i0G~-h&d)@J%oBWW1Dxq?KL z`#mZ6)IG;h@q$lBfOhnDfO>g8K>A*oNRpm&zUKV;YBd_sc>0A<&$ou1UR)38up zE^WKG25_pEF*HfUPaTJ>5$UIiaqROPt!xzVYi{R&YhVZTy9xE8XFq=k;J05Be4ZEf zY++m!z(!2$}^@BP8ta6(6L_&8kj z?5#Qg|0UoFN#aZGhK|6HwgF;Og@Q!#Sr~fBGr&q2GNKba6_M1XI%H09{#q5@%ySRX}gq()} zAHrG;H(0fPKM$ZcBG;4u6Tx5WS33bGy$${`&(JLNHa3Fmty=iuj_WyoLIC@mhV;be z#9p2*PqeRL0rYcIfOfr691X?laNurmw9|}J61^l5mIbfQwPo<=I?(G$YWtp>XtSVOuN-~xdm(0tlEMHJ*D@F9y z!s^WO(o$R5ygQZ@E-B0|n@@@66js}c%QDN$stcD_vv^6Nt*Y?0!qVI4E-Wk{P-bPJ zt-3H{$^7|+mEIIH3oFYCOFU@7;g-ts(!3QFg&w%b|L)@IqTKQ&l?8;!DqBnv+*wv? ztB^CwEv)8T(<>Kvlg%l#>fALQE@MT3k?=J*^5!5Y1XzSXPZ(<`?5x#sX0)k;C1U z#ggDioKs?}o?l*B>M1-cEawPzTp3c7p}oqHIk5ca6tWad21YLkylUn`3Kk;UTZ+qy ztBQaTV$Pm6$5ytWP@_>zRIWSDR49ViqhNKLt-_-#A)Jo|hzK(cCJk(6LD`b3>Jn>J zk*%_D9+{5y-rVZsu~ut!QDyluYe`|*g6bk`VP$1`WzNh3VDs*podk5j^5wR<#Y>YY zX;rbcpu|>HWvxc#TZJ z~A*a&vrG-3`s`2xS%jRW4ZKafL-d#S~7TQV!NX?a3os=q< z5JG?=a3P^;upej5F0ZnZA1E!K2Qir5(SDZ~qxdYcps?EN(Y>{zx>CRkpk(WkvclyR zX!nKllnT^8+Mcz5wSQjvq;Xs#w6?-PvZp{DRfVd)Qi~xDhzh4AtDwtaGQJ!oAjRnv z3FetJ!D=n%3W2p%6;@X3=_P9pQFDn!>g+sg-dJl^?gVSj%-nI-5>~9L@m0%g6-W&` zr8-U;FKFfm)_E4xO(v0BJ-(oP37OXH-12c1ORBTbM63&zFSk|{R#ugl*-DD5S6G*h z!qN(q z5i+4ImRH&qup;E;f$WM5*jGi|ZQMK0mZP>jv@%;sAs3#THF*Wd<27fl1YgyO(#|Vk zj8Nw4!phR(GSCs@GIWl-UCb?9P+aEmK&Z`>`6WxLiiFixO@MnVUchXU>$+-UWg#qY zDJp-A_JTQ5&TWeEeFmjw$e&$Ei`Dhru^<%MQekOo!q#)c|I@yT^5);r6V!H2*~ zs+N=%l6xtrSRoNH(-9>q;if}Q7Z%~+K$a=VQRVhfYm-GG3e zdtP}Z_8`o~1_ZR9e7j|Z&|8V9=I-#U|!Ggld%;c=O ztkLFW6Lm@!by9MIlnV3>)mifd`-!3>PMudc-?pTr+RD;;D5s6(l`Xi7T1>4duULYC zLt)Omg~Vqj(kCU${c+O7LO!JNj#Z$=*}2vUyfe;Ph$gxe4#!g*;8NJAfjTHSqb!tl z0xaX+*=fs5OW3%jGAVf(jbE&VRRy++LaI^y+>^(O+sy({JTBVp7+Hf|8s<+oI(0l}pO<(BP^tTF*ec zTUI=;x+o7#J8KR#5nsav3{6VSI%`hSxOr@J%|>um)~SJJ!aSNJluW$4l6o)Xj*3Bj z7Vt?!mg?+;1Zfqv%Bn&P;o%>0a>!SiLG z1dU>|XBCf6PEN_n%Az*MrAp84mX?6lN>9X z%4uyNX)LVJx`<5?1KZsM)j2UEl$;Z*13m{?Qbt_}Z|N9{mRGFEo;7zYb21pK5{?6N zW|EDms?NdCE-MQIJ?>?A^90`4`jf}1PD0KD^<$ljnGExIR*#O=Mv^j@rqw>JQm2kl zpEjH!NAcV$q+p$|*C3NdSMB9B{HIX&uBxCZ zYxe9k4EoEKU|71GX0ByeWU!TZ`n2pE%wyD{Oab^~PD($_IA)^`vf-SlXG4$3YJ-ip zt@CXqRfTLqO}Z9xpy`teF$ISv{Kq>!DxJ^hxGNK#5_D*#c{Zw#8M(Ok45&mhMwwfk zGLO1nP0x$jplVyJ=bbC%k~9wWhGiT!%)+?K(+8?f`7-J(iPstHV$_zSv0QHrvZ0e& zhgEWgB_+cJVUUIyS>d#tz)nbQ*E*e_HD^v%_H4`;)91`d{}Fcus(~h|GfM4I-*M`nJSBSv1%LjZHB4^i%H-AatrcNzIUiRpIR$xqP+K` zhROyYs*9EjG#1LF6${cOnT+)osNF~FT(@$a=3ZT$dKyyFM6Z2hWAziWiK{Xa<^@&7 zqji?%l#u6#|DU-Oj)tu?Tupzb^;$V{|EBhBm@%?ZdMZt>vdiwwWhxfEIceDIb!2k2 zr_dRxYrBZ=AE%2JAv_0)3ZFt*!_HK-1ng+%%xL;8KBiYAaa*iRI#sru`dPxay$2xA0JieG6Tj$xTZ8WW+MUfOMpP#5x z7kEl|^c=YI+!X2{lg3q+FF~QobIO<9K0kRODTnBp?F*Bpy!kk27N(eG1(<)6>U{fE zz%GBBegz$)JdXD|RX&X7?G~Mseg`=X9c1zB+-cT{7*o)yuR4{!0#`4(XYK4zmPE~7 z_;%iz=?)LzI7;y-gLLaZCQeQgV`ATj4q{-8hY;nJE3&S9icSOZ+;U}Bc1EUnIHMTY zACK|pHUyF5v|qprqkHd(74=@_qH<8_IbNk!ul`t-4{=sgd13Ux$iSrFx${(93Z9vhkm<1hQ_4?h!m& zqa7ObD;R(WcA$F@&(G*LOz<#?2jJ>{?Pv{r`K>&CyaqmYI){(dz&ivyRRe!Mo2R#E z;P=nq@aYws)ro0eugfA0JZ3G2tNZ2+h`tRu)OvkdrvY{=!<(h_ z*b3_T9hBhd9;l*p8+m;aAF&mNVTy96pCAhlBkjQEz_zxvMbrO841m7sZGbH%a5?pSN4H8^*X^g5-f{QMV!FNgU z*%JRf5?pRa%@X_$Dg8kSo-4tRNbox)_{S3bE(zW$!S9ja9THq@@nzVP68wHCeYXS` zTh2JPx7YsjrSxVAK39Sdmf#B{_%I1xB*CL4c(DYJm*9&e_*e;EA;D86_+klek>Io^ zO8rfj;44%ht~nBXr3Al6fo|!c*hBu3?i##ypgr0c zbu22{^j9@7+%e#`a~z9*g7|(Z{!hf)rFc8y#zBl1OaCv#W2N|)h-XOguMwXs#lJy( ztrS0p_;x9N0rCA({5!AS}DF1@$FLlLB#h<@rMy_m*Q&?H->ui{|Vx;Qv6ZGGo<+Ah|iVc zn-E_s#h*lcyA*#0@%>W#mx#AZ@$HBk!@T*whGKE5*M=JVT0qjrd$C{te=5rT96-w@dL0i0_x;-yz;E#f_QBf0#G_ zK8VLk@nFO=r1(I@=SuORh_996;fQaS;*p5&m*S%lZ(Q?Z|h-!0mIUs{ntnb?N=n1)C@#hDF4vyMsd8z{*Eaf! z$`_;ZLHWpD$X1$7)?-&=D+5(tTA5;^uSlkgJ)*6sI{zk`>HKx@zm$!C-E(y|-m2!O zmD?6`MRNa1<)g}-9LwZh_dRkqU!~lytNCf=-WGdBayO`aRJkkTnA~@LkKCKCQtowX zept`|ZS7tY|hCL#Yelj3B3HfS>}!|lqEN%nVwX_MJ`4)M<7rMm2Aap7f5Em2BD*R~KPkN6Oe z?K-p%fHpr?u@il@hPG{}lGk9gxYCuibJ|U#lXvV;S}4EYLGO*VKi=bZ8ys%%EgGsc zZATidT;V2V%NfYhX&RRNC1j{GTAIG>tGJ>Jy%w93)<+hFD@|)jra0g7q(P=N&_PUe zs=XDs@{Q`H{3^zvDc94!_*(=%ALU|WP2|I64TWA% zmP{^dKFJDwcbOuRPng1z2fV+24s;BCul}aPWO1!G*36mFr)ExRhSGE!@~$`3N1hlI zmAt|5SR~oY48!`!g*Wy|D7mh00@)6p-{f`lm23&|YP6G9Q>b$a^6FW6D{S}{$GN++ z9OvUKF4(r6+Rg`xax!66y2~7+v?TOW-U#Zk)+P2+j1AjGqclPIepCg{IAL3cmpX%A{gw2Ig+$!PJa#-*x5jnr0KK|vv^9&D9m98ep zmo8hU{-bs1n)~|FtvCAThv!ay`Qf3NkDQmQ?^&>SvXfh&Z?ai!J?0y)j_*#iW8ym& ze2w5s`jy+6O=@QaNK@3u+XijOvj~1l)nx;GpWPfYNg2 zcFe<98XY~gn2SR{`P2{P2;UsX{oOQ_f%HbW&BH$X%de}Cep9vZ-EYi2nMY5%e))}g z)zN2d8k*3aX-6jrx}KF84oXYu%z&E>p)=3ip6*Z#v7;da^JPBsCCKp(WJbLQo>L*s z>qtX&v>q}!AX72Pq?iwNLZ_=lm<)-xLFNw;w)RmLzigs@AT)97Xk~E`>a`PTLQoHn1}j5@(i0B_pCHfGqe-yHh3rD5OZ&3h;@~+xDM$OWBw3nMVf4sneg#32P5GJ6RBUL zv7(|_Tu90 zFy}<@KLZ*UU?%9>#q1{vb`%QwDA0#FUqu=Pd2oKi!7r4JBRxC~N=gXYx(znG&KOo7 zU-LkBtYWUG^(aakj!6a=MsajLx&r z6_s_WX;@bcd}f4c_@Q>Ds|YHq^IezwsgQid?p~{$+JQR%^2?Q*7NT6{zDmn#qq(aH z{X$1yCE08kehBTe-fTj+L$OaanY-$GQyU9$V*Kb#46~#LhbgI1rl78Eu!|@qvMU<= z4nijLBN*oxENM}Ll_tC%!&S6!Vk-Ic+ycdZ9`xitKYRRv?mFl);aBOd{l>6E!D}Aq zPB0*DFxDp+f)7nK^y)G}mTgA!A=1fl&^-a!scddzWLFz}KEZod-U6LuK{wN&qfEzz z1sM+LjQOb|V{m6L9u^j3U=l{vYNH+SJo&kHIGbvWdquIDcZQ(7~Exp z5B?K;Ey+h?wW3(11^1UV4%tcm9p!5^ML1VO&i?_Q8u%OKV5TCzx z4LJ3G7QpYpedEC4^-E$EM^Uii8i9IPhOtAtaoC~h7c)0U8HRVYqb{BtXs+MR_zYuw zUIZPb+ina$l!tU%7>?RdxN|FT9RowzTp75!OE8E zffg5=Kh~t#8w!jq?K^_(VUTkh?#brfLY|GacXfY+wn1}pb*$9}pWvZ=4z#tLwhw3- zzed1z7+bdQFtiwmAMo1|C!Vh}o_BVuytct#HJa}7#M8ms5x2}?h8@zFB&s+1t>=}z z4@4iH8}rbWhtljFScjO7 zG#yxzxD$4uwsSN3`5>Kn5`4N(nogauHTB;zpAU4>gd&aHUfI}_=0lLby4(HKF0@}Q z{xHp_fG+|59Uc5Efu9HbTRQj>niqloe&8!~@;@h-Q6o-Tip{4F2jJZ`i$r`bB?3#sQ%eH%|K<# z1@zgUJgKC#0#5UP>ZjUGBb;O}_zr^W9O|zF>qDpymko8@igLAM91=5cihY(y(`X9o zCj7PoWLv|XZw`UIn!L7!_pIf0U_P$eT1*(?6TNo44{?%n8|&pTrlc@^@91aWq14QY=|2g2k8*x- z9%D855Fgw%9M=k*SsDJQyUO4~d;JyGbZAU)WO!1hi*$GpxS*RqR0)#oh{7C-B3g6-Ou1td3ODsLr>c4DE6Ku=W+@?1yr+R;9bp$G-6vc#^z7 zdQ?fFI&NK%?xM94%GbPRxP5qUz>v2?&AR~kS`qH!dA}y-4Ol1eEN`UoUZ7-Pe)vZBN)DG2If&#_^w3{DtX^R_Ir%J?X6g6jUY+WCbMC&_>bMN=g(IkI%(!>(sW|oN4s8Es7Vtv z$Un_eZJNRUX&%<58RDPjCz><~A^vHe(xeH}N%N#8O?J3HpIw?X2|8)8zs*;NI%%*s z&L>T0n15ccAdS{u#!SSRANKO#D_hmY#;I5D2{r~;4YH9U%SY-NoOj}pOSE_gI( zc;KDQes;TDQ{DufG|P1I88eQ{Ivx4oU6+3Kc39voz(1>zBj|srjp1G8e&v~`BWp<# zmvt0msne0Qe=^610soi|UM=f@0A<}N=z9adNrzt5MbBBT3$2aM61qAI{8Kvg{Y9OA z1^h2`@P`HdbKo(D_p6IBXd~1H{sH`}I{2N!cK-^zQwM)IgVX;J_z?6}TKP{1{BMB| z)xnnt{CmI;2EOB^`yDRK=cwQBj5A>GPf%AY=3E_vFdoC4zXAOv-J4@9Y11)&90a{~ z#-%&VG*-tm#Hj{z*S7E6c^zL^Tok9Y(=pC&#kCcA41x`){Aul#(y8$xHfJ(Bk0D(v z#s)NA=!i>a`H=pn_Ei?Aze;Nfk-=E)rqG;WA=Du$XV4+Ga|%3)(V z8YgyQoIt+CT)eb9VST!*@%l7JXKg=wBi3siag#6}Gql*oVr^E88>0J*aqbKyWiE|j z2|h?krZHJY^c4FoD6?m*i}8G+Bk&2p)B23o9(S^}b3;oE@P7b)VINBx{O$OKLoH3KO~GA;8s8;$#EY|iQtb#2DllOX})PPCb8z=Mrzai4*?NX+C(_Hob=;o3mIQ^KorkQ+q3 z5YLWr23HW~A#JrZ#~JS2LUl9Ft9!#cuw!W+vJG*PgXLKeWT$y@OwlC!1mx3(IPs_@ z9yfV;#0Z+!%piN4X{7U8N{f3+yPVSA;7!~1w!}Y9@PB`jeKgS^PBe>%=6WxUO{Osk znlqE^Lx=`(qIrO5;=D9%P42vWl%s8BMpFZDo-!Rb^D<$sW*~aRiGDWGM|tTDp!d)m z5HvYA+s~W<4dO(TPBbIDG;8*VJnJ)>NJk#}9fE%6&GyfT9&w^iBKim~{kFGwp4%|z zYpoSDp=tJyhz4<@SwS=*UYZy|!|O}XV9xgk(6nZnnTP03$wgiI3asJNC(R2LxT}WcwzfgPz*}Bf31I`_@YrT2TdAoe zc*jdyBb(8WG#ZtOb3n`HkVa*EYu{1H3lYcsahDluNz@OS(WdL*x6OY{u@5&ZO=h#= z+7Eojo^;nfTw^Ro`(vQ_C;A^Z@^P;o<#2xiIWf15037l-gQ!0Ptn=US57=KpJ_YsZ zT#Pv-;Yr4hF2$#hngv?)7tminds|#zd&b` z;^TNfIt8?8nTp+N8r~IyHF_8NMVuwV8sc#0P~b?X?oSn0L+u^i2I!Ugnd6Y@t<&zO z&ShGfT7i3Vh?3HFybtOM^X?tg_CuVnjPkU#BdrJec-nUmc(x%<{O=loGW|`e!`FCQ zy=@TY&!6(O*(Rj#xY=v7Ymi1>lZn~o&Qs^mE3q~}^XSzF61)1fa9)#$7uEo1zWpZg zT9)ow30=`zpW4@@7rXPC?yG=~!gY0Y24y83eQM-7YJyHw9en^C>4x~9!#%A6p|4P?Q5965*&2i6u<9>=ikK|)xdCc~o^8Tlmw>181y-K;qz{il>k&S<`5*XT@s7Gb%=x2_#i{pX_ic0;Hefu57Fa{pYbqo6K){L#l|il_MV=>(6j z5YkXid~Yk1{HV69&7*z!AV0skvEF{E{-gNZ?kA+a@e_OWwTG^!Wtp)2HvL8r*jcM0Yw?Z}>WW%#O&s@G0J|;g|dE*Q4 zwv*f#him1|AM49ITW9SJ<2D}~Z^n9*6Lv<=z4EbcOzV&t#2<45KmI?^@E_+G{j0Bsl1V@~QvAFH9)S$7x?T9uBT>$IZH z7r-8GrxqfjB{3-PTgTec22hcSfwJhLX;x4fM?`(Cew9J2qo+&Vpckv|)H7WzJpal|lIo;<(uwcx)Nyj7jArhM@1S&gf8Ana!2)s7d7FJ(8pPOg}@I;NWg-hHGp{6M;w=VS`s zr|ikcp|jtC_FWQOSdnG(E!A|){8I)5ghPr2HuhTj3$NHn#!x-j#5^)=?LzGNm>%}CS z9k6Y+ckiM5zuHMOjQK6mS^SNHGc_$9!<2fQrn<;Zcl>*^()-2dH&e5UKkL1#Wthq=I~ z=-@Z}i{obkpQMo!GW(6;^yVAt^ZQBQLC^1dVI9+iK(@uojX4s{F}QsMbv0k5AL~zZ zQ|LSz`SeDe5Knf_0_#F_FWaovUdhgwO~P(TCR*$GGOo9S>^A}Osj}huD)kc{dnnc! zuS^x^3P_fouSJ{J*!o+LF_5kA0gi0_H@LolK>mU1PqwiypvTuyE;={Y8D}iLu)qZS z?}c{Ydw%YJAZuE|Nc$O6FK7G+OVj#DOVe4gPxw6MbKT@W(02DBYzOYNsdplL%;Mvw zpFcz8_}sMRna|*B{)M%yFR|32E=K-=6O`@E3fpP-wX0ZNLw zpCt`zpW{1B*N4^u)@G@-h0`gbOsOsnY$`^(_pwq-X*ndvE@Qv{yR^)XEd2NDh*ngXd@6a>(_8>nq zS1!589Wi*4OKRQ$O?^uIGW1&sVrJm6jOnBYeIP^aG^o@BPsPixJJYfLj!TAw( zKNHUY6IS&bkzk1LSF~_pYQjF{ju~_Y1T^VbQ=hTQvMGMb;9N?-5c|z3J^8_eB+!Vo zv#=NbF~f-Dy=yp4w85OX7i9=^euT{Byz#)>J-&ahU^)~tiEW=-eHD1DTap6Z>>5UaK_Ou~_^6caze zE09gx3>xL55PX=fjIkMve%If$E4Z~2FojFOucdLp%>1D zn4IL-NO!1j>{&OxvOQSY?Oxs6LF0(lID`E~ypMvl(F2ity76qI0 z6g%cmZ2xdVjAHME-^oT_KzsJ+%t&Wn#YOW`qFIQx{jDiDF~MLyw0h9`t^)Xs@xYN! zrSmoELulML%z6J;=<9Iqg!V14Jq7Sb1gAX(#lW>9&rFmz5n<1Pd-nu^hcaM9z1wYa zxUq-1{Q%Wvg!4OtvPG2}XElaI1u2VTaXzAZQKrL+vmQ3s??vp1CEM$`-r~9ldl|lB zWp|W#Hl&#NnAR+w4ZVrHhh@^UpQ9O+71Tquy>q{mnu>&P09A zz!)tXXEaRgj0V}y&%jr;H?j}*tid&f`KLfO@;YdUwnjsn06L-%6Lu<|t@!wy9fEeT zL`!xagmL8zK`-0+e%OTUPd5vCn?%p-TF{bT4J7wE(1fCn48m5A9fdk$fum;!yRc3~Hb?bT1Kdc!$)6G|AAOJouv-D6ddJ3qs+>?Y>e-W#a?4P_h&v6&m9w~&;2d@2hLt3o>k(kSL+eUN51=0u-j&PLBR zmjJ(n=_btiw-Z#}Q0D-oDMDGbeTV8FvZF1I6D9@YBa@S!>GkVL-@FKZbP>+J1ouqa zTx;le2y=NmrCE!6EAFxO@BxipCyx1D;(z4?q48WTSRM{WS`q;euw_P3p7R02bHsk>BQ_TgD%Mb6Tdjfbv~` zt;LaG=-YK2&Yk4Lw^CbE$H8bHryOxO$3J8%#>cGPxSphP;!MS!bS z*?)AwuYiWuNt(?{ULDT0nGIp=><;G6_NhV2sSKfpeL`laGrT93|IxdEsrt)J#&LnAvMM`z#m9vHPJ z7i*>s;QKt@zahqbiF8I{J+F_%V;C!L$NM;Fte7p06~p24KE+s(Xo>DP$~WGe9u9uc3h2e;tVmf;||zyIP5OL5PIm-q3gS{ zVS9Xh9F8$f7<3Wg#QOJ^B@d|mPy|~WBwf{@{u)I;G!J=FKjhZwhthzn8ya3;E$W!g zbS#I>2b)3!L*xeNTOK%2kT+Fe8XHS%?HsxR{I-#@67w?1%Ls^+!Kv#7SF6%am#TAe6Iocb}w6n29n`n0y!_;GJ9Rjv0zhmP8Kg*4jsc^}pGEEnt=b5^VC#_GrNJW!RCM?IQq#&+_K`_nYnEly10^ z@(|X>wwl5g1>=1Cv!6VK_fw2;z6@MD>WMvHMf~?2tj|csnq1Sjrjdz1hFz$1Gw}W{ z)JHPFzXO&p!=T@f0E?Dk(C=RW!*j3XX0+1> z(NA3inOM1km9!XkkG>Q5NQ06_^BuZ>aHx_-dpp^ExRMs3-sAjrsCqwINu#kll`R49 zun0o==sgxeC}Tf@$Kf0op4}cq8{=icIU2lUFJ|4%_F~9HGLYV}pL@t^)YDA7SB}O~ z)DD!4nmMzOhWtotCarrK?9-rEocC&KN1S|#!JrIH#ad|fK#UDAm;N=@l&U<>r$f37 zcz#4O@Mm@*UE2`vSvdo3I2&zwI@h^<@kn}Db(p&$Ncy0~7{Q`Ve={?u}H^)B#{0cq%DUN>(`1Kn6Gl5cjnkM8guLOH(#ojrOJp#!41A6Kd~mL7eS zmrqbvKKzx;C(u5t>BIxJ>ZQe63+h~^4bpk;jq{33hMS2V?LHb}%52Uex;Z`WYP? z$CyoP7jm0E_b+PGA7eMcrg3po6&vly@h_~LwHP<HYq`!$NBwmc*M>-o>#?EeL$EfLjWu_y;T<&(SYK~881Rm)0f(Xntbe%% z^+b7GgL7V|pfBR_A#Aelx(vsoH)c9EOqk|){D)bNC!i1VXXyLkm%^MK*Bc#Q-ehu| zn5a0uo@#J}_EEOfV0{z*_>CtaL)~cXNr~m}_iINU5ixk~`naY0_t1?S&mneToZbMP z9$8I$k7nL}^Lxe}hhb-hUqbmHM2Y>VRyG zu4?+@EWa>k6Rz?+nbxtX|BJ=D=&Iht-dNOCDDslmcFkY-z9*jbmq?4})ya=W*9=8n zFgoh9iy$-BY1w+OCysS;ypJt70k(oYFdM=C zzO&%}GVF`$kL~Zna}}}++TZ7({e3s9`}>Sye_v?VHmpZAf`<0@HK_ah@ZPNl!I$M24eGRJ-9^WzDsQn zm`^cZpMthf7mGb#n7`GajB7Awjafc`e01{X;I|cX74ng^{=FIgoorI>dp`V}+8%%I zpso#5+vzx<^jr+kc4(hfBl;S(-H=^ppbQOYH_E=)(c^GWeMp07Gw#pO7oxrc$@z{( z&SE-me2F&o64L)S+SCi+8>mga2%OrcE}~6!9I*8K|7ufvp}$MDskeatZ?>te;QxQw zrdA_=y*8DGItkRKCILrnsui@_Hl^3UQ2U|&={WXb$bD0P);_%Ng1n4=g*{KG!$I7TYTN!Ac)4vq=k14f z`OK&Be385A_E}z+Y-R zyS7}qKiXyH{Sn)T@G_5AZZVYDcTupq!hE&;eZWlp7Piar#Whd)=c?oD(2)j_j1@V7vG3?G@ry+3hNIpJJwY< zVx9LC_TAE%j?SCX!6U=*)znO+pN92Y#l8*C$=fpxcE?ROI~s483|w#E`Zz{G=2pl> zbNh4G<2g9iwDjioN1$_cZcphCBaSiY#+W1h?d`p&%wf){C~wcoSua4^#tT`AQJ15@kcy;Pz$9d?B)*KX^CDN`rWMB>!iZzEC ztT{L#$5yfCkdOXu1j>&yxZst6^@~ibUrclG^%}1Z8n3_E;k;=w@V$ZWaL}I2>$PpX5)H{ zH=w2G<3(6kDTYlfN}lE@#kx*4Y>W10EyNx}zP9ryTiZzxYdg)5i^`jhIS#F-)4bqQ z@WL~-joq-lV`~T4X^#-St42K!@)7XZA2X!rUQ1K)Bumr68>cx+u#QCeVI65Ets^Di z+4!T#V;OkQz zJ7Dv1vF7SG?r7l8G(7!7vCcePop-hsDE2oYFXeL$bR+vMTK|j!%>Q}1;-o#k^iF%K zCwl%Gvret6Fy~#M31@W`?tBgRyspAfSK-dv5vRIp6m``g)zv!SSiNr`USw0ezPPUo zb$$c=l0C9C8+m>=gNEzKcmEqbV?T>`i_71xP}@ldjn`E^qKzbg4{IaWO=IswL>_rm zKjt-7?AI{c4Yd9UUs8*7MMg@abXhRIL;ba&9kX

$AF0$A8gSe_=53Y^hl1-J8YG z#U^1dj2GDg@(eimu~lwzTc^EO>4~-Qb<;iCfT4 zsV~L*k}j)VQhUrsyM(Q?Hi`F#FZzS<1ynDzKk*;ne**SV4Lvejy-rDE^)h&%sJl?- zhe*=~A4YQ)Y9mJwXK94a4JIYsBF64pHW4DGvJ-3$Bvu#O*&y^SA&cMOuFKls?>KOkN6Pn7OYjS*e7Sa)B7Z?;kU?Zlqn z;_DRGqv4iKWUoap8XTS2cShfKxB>CR0m1bPuQNFop?&D>T}nln>cN}N4WM508n8c? z%DY$ewNC?2&oXYomF%YmII{EK;kx=^#jz1^((Ml!KE!zj@Y}I|G#kNvz|i7C``3P} zh4e%FYSs^gzeVVQFHM0Drg!AeMW6pB+RR%B$M9VF{KM(4J;;yF8x2OCn$gxjy39Eo zoq;9aYK2TRUNWy-A>Jb&-n9??8_quBJ1&M(bZ(90*p0CO$$;=!@fb>S^jDC5n`6vB9GzhUDd-*bTXw}JNBkqxqWE1sFz!ZF4|o1$j~!3G1~H=nur zZnQO*F|>Ya@8MlR=rb0gYzg?LPXgN8UZYZ(fHnu)veysY`b@SVsDAu_e)UGs(tb7c zoq4cJjC(?z(J1#+?6#;XJdVu-RG^D9U z+pj}9f+eCoEJXVcrnc`iIO0XWRrDf#FUoh1s`|Z^o5AD4f_Jd@!~fe-4`Sa2_D`Q& zim(g;XW&k*Ksb#yOMc*9Q$PFea|7(ho*7_2|H%ORuwM_br~Q6_ou1L9fo~P|P1^8$ zCcaL&BWkg-*bLoGU)i|FY>31+%%bpJ9qe)IOZ``v^9=ka#kb>I3N$V`DdHR-;iSHe zrN?(g+pw>@!zVu6`5EHd#Jc(8&>7|32AH2kkQNIbZw>BL2Dfm82SU3DcS~vD_yWqe0yfG?q`n}5dy|tm;hM{ZcY(H+q z7$wZvZC19JamGA+oTVvfhb2u}Wy*CZ=85!8iqEj7a31?@>A7=^33DnD?=VFqM#5g` zj60pNd<118os(_Q{?2c4U4yhM;hSuzlbEps?d&@naeeG%NK4<%p#5F%(EH%lR=J2_1{##J$U@V?Yc zPBRBIOonR)*&7P*y^dN_%WcF5`0a=jukT2X+Bw4Kj_lf&NAJ4v@=gcu27EtcFTUH+ zhC2SNfSyf9;;ccG^B8!23;i_!H(~|O_ENgqAxIbHlkTvZ4!CzH9qehFX%61qso>q6 z^xcn0oVyD3IkVsOPqr5h~0{8YRU%pO3`^m#p)*K(c zJ5=0il2_tu8O-E;N#zUNGc~?^w+Py|*O0uvd>>PBYn2rD^#+$m5ASoncEPt5xCd)} z`93UYpIL|V`*;_YtcPVP?h){fllV>_!sK14@&)eRpZM}E60{Hg6nycHE}5@Q#npjt zl*IQ4=Ub@q1#Z%MU%q6oRB!j=e|Vw` z=dtOzXZvxpT@QZ>_#*h!p!J#WDKXKb+l+Cejf3%xOUS0&7Ck!A96Q>A_fnXLC5%=^ zHO?lPNN(mAX`f>pm%Bg7jeC;&MxB=tBKRN|3Py!PD8vS@SQ_? zU!q!G+f5SP$Dlh-?~d+cKSgx7r@VehdATjFv^e$*3i}L4cJ0G^-a8)djdw9XM|i)| z)YXcE>FBt=j&`X!I-swkM&L;|s!n8mWNP(sfXjH0WW+tm7)COFtBz&SwmmT`LD7=I&6s;}_xO|V0e7Gn1{zCHoThhg~k}e)XnKC)ea-zY#s*8=Ji!Lu+ zx=i;p=;AotLZZVx(Y-}^ec`3qcMa*Hub(d37rI&7qOSn#e2xxr=6I% zd>JGk?n%C%k$lI!^0h@vy7)WFbR6&7hP|f{4enK4+(x?i)JvBx({+RH0H?d2=x|ST z)s)xYyfpiwNEc>*UEsa`dVb;yoEvAlDA3o%r@#klBM&0)C9==h!R2%R9rEFx#*MQ` zzK^`}wc$N(L}R1z-sEuDI;Z)DXmC$7)JB3y7e~Ex>7b)_nu0MHjUSyzPkz~gxx`+& zhwrERcj+Ge3*9%-J^C=Zf0ORfPtyIb=^lMC-S47%^!IfC3hrr4LHER;#w~RJ5`**i zgg?*V{C)uHp#ftvN)wEGoQFxIaUI3mkq&YuV*HK$E#7a&tMC4~Se}9R|D>0G*?0Oy z+6T2B`cR)c2kCrE=|zmKQ!ljZ}RG|y?$ICRoHt4Xt7C(SdOG{rh;aCXS2 zPP28=;Ea(^ngpFRPifKw>7;p5lcrPWJ6KO>(ggaRR*+^t{)x?4$1G6nO@G5$8EhgYRol{yzu))gJ%+PvH9!gtr6#p$>j0 zzPCd7^}v6kgD-iP|1GDt0e^!I ze#7rL{zt$k>EOrwp5yNTeu5tU5XWZ&f0qvagutf*f4>fX!(mRJ2E0uVe}vyPc7|bG{y>d_xz{RYRX3daM=r(c>GWKJ+?s9-7NNLiAV*@uSDuoDaRucz+A% zmk>SHU;OB?*5*U6^S#=2pf4nPto!)UkI~TUd{?6y^mh{dX&rj3iTUKO^IeU3pwA-u z^E&kL8v0=W`pW}-3ejT?&rg1QJHsb`oiokTKz}XKW1Z5E9&1vdKcdd*KhXJh_ju5U z5k1yM{pe#g^g7>7xCZpSi5_dRe)L#7^2uLk&q^rh&mz!Tv>!dbm*GQ?H4W`~*IuC2 z&ILoh9=gCpqKu-Q2W_`d#<5_&@Ny1}2 zN5$8n9TR;9@GZof@L1zf@g4Xs4&f&Oe;D{y!eiY>#ZMRbWZ-`f{KtgHT9ArwL^~(? zMBw)We}wQ@A5!sVfsY0LJ>Y3Qn7*^8;)^0UeI)REfNv%|){#{FLHGgUKNNWE{SMv3 z=2cnF5p#K>?g$cI;6B%Cn8>pke1emUSPcDczD&pXAr&scv_431(U^# zSAA^__77Z5T|>WY-uBK%{QR^kr~FJbAKzY(dE@-4pB-HX*%DdVay_!EvgHrd&<8l1 z9!d0gM$GcUen?do&IkK3an4?rFV;t`49?d??`Lp+|62y<>!bT||0&*|V}O64HQs@UV}5^x-g8N39Xo!n zu=gjQyVc0nfSbSh+2r9!L+?*+!#LfMtf&BqfGMqO6c4z`Z=`2P-hR)Zvmd2xdESg z+_QZzbPg2fWPQ%wP8DZwUsKQChIFmL-V>%X`Rpy;A^j|5^PC?LeAwAr>{WXXxYjs) z!xPu_2%*@oarXsxgxnT7b@uYoxm!8S2Rdm2pSv}*yos{voe}JRfzCl0T3!YIkJ#I? z9P8xE5SAh=L8wNkLa0Poj8K74j!=eBiad%Ph z55$$#CC*2kL0uJL9|k*U{eyKPO@dhaV`((+z{UF85wY%fgx39D z0*xE{Svup)_*O;`_JIZC97jK#=fHWGm3XIorpbQr%u90)9^Oz%`|8|PN|SqaABX!U z#pTYW`(6%r6!ynY#QP71TGGyAKNQ~Q$M)Y%$2+mk;>>{?XWVH&RQnG8j)yngu*C^@ z_Me!M(1mYnm{$djFs}+8LHpyP4E?&4r20tO8}$pU|Ipc#VGkK|jprXeO7*4g`Juj< z_VoN2^0R#izzrXSch=+icDEbvw8wkdJ0NRkIP$+9_arOoz7y|`Z$>>Z9~C{!zP-TE z@(FmnS$prER^X4}`yH(AYT5ao#NPvlJ$s4gz`GUipW%BMMkgOXs@R)V++Zc82=#*J z7Do)dZ+VaI@qFUQz0cxo0rn82t;X|vQ`~6mquVtRb#v^QF#GxWQ|v+Jn9<}1dj21K z-vb!cRpxucBy9*;ff69JNQV;Jga(>~KvRo0X+j%pN@Gb|RO}=q1BrwrO(t!yXj4I7 zy0U9fwAiAiExU$@F7BdDSG1|%3YyhmSw$E3g@T$&)TDR&UgOabH01-!*{~oWw84lu>ZT@kG359TcsP+8BCk?yEIQBoqPXH@1G79 zoA)PX^t=L`?nl#m3UTfm+qfRLuRM*kR=iYgZ97?=ule4~u+zW)waB*WkEIgh#VG~|i2pN?^! zFwA}p`D;UbN73G5=EZpblkdLqng09WQEeP;fNjC7ZM&Y!qw4r?AVb;xZdq9maDIE& z-9G-e$bQ)^E9(KH$qtC@=f@%Y0%Xj2N3}TDi1ob!xB}Srk60VwSw?J+L;MZ_XwQMh zXQEd?BR&^lb5>EN@N5MSzx(rR;o+Q$ynea!+#tfUac5aGY|48OV+6}|mdCRc>oDt` zlfM#v(&YcFNByw-Y?S$bA4S=qT@|9P%trbKkuQcn$}rkK!}l|cc|s-b&bsj%)QM-2 zm#^dE`sc4F&(c1f>n5Nb`Ouyc(XNuvk6niI2@|%352PIFIRC33b$s@xze~1yf5-Gb zzj+q?ISZ7}(DR#TBD`dGH~c$mXGHg9Y>SzQ9_dY_K&l>55{nwh&!8cpQK;WjGm2*8*5E= zd%Di5u+!Ut^d5jO5@fEX48oM5FU^g7HnIKG&{nXvWy|e?+%sBkD&-KS-2IFT>uM&h zD#$2bM2~#(tOe%D=|9)v&d+8Y$H4;1bWS&0hU2ac%(s)?j(Gqke}U@Lzr@};@bfc zU$I%I=R)RbAAJ8j%BR62KaZa>vJ zj@66W!AUi!umPhV5q^^Yi_PT-BA@7meS1V_#B; z@qG?t%-YCR49nU`y29)Akm(Aq!&fN0UK@E>;qM;tW1dlgFu%p7(zGglTh{?SCeH`{ zDTFz$K7@Sm`?HU6?uh4Lou7%PU*I=TF~(z#0H3qlFmG6f`9lfj5yiXDtuy{+w;O*m z`(55FkG+Y1KpK>ObB3u057#H1JTH6rt$o?WbJ&AtkBeuw2hW#WJdb(saDCL7o;nYn z-7cQx9z5MHo-7ZZFS>Xpdhm$Po^9usJ@#*|XC#(St{P_H3S)J^a?hXV2z2?7>5yJ?EU7bMx#k!KY}R zwJq&O@M-e!+3FX1D(LU?pl5$s%O`@q)`PxhkEWkH5`KJ*2fhAzO+O3zhzGsw+nPQM z`eYBEsMG_RehT#I9`rpzKMwkp9`t_tj3NI=L67S*26{i}aec->KM1;)&sf=Et$#o0 zw|m5&`aMnG2l|~J^gTk~1Nz+_^nUu3A^u&US9{R6{;Q_%1ij9Kp8W$&-wt|%2fd6w zY0$qF^hZ4Csq{$$eGBLx^`Q43)$~oEKLa|S&G|hq+8fXIYJIDY>(t`6mKMEVzgO0; z_HzB|50Ih!cigh_Y(H}p*&&hrx?5JB?MIXSsmOkD9J1dN*&S}#F{Jq$BKw$Ib_{7| zeW9&BI1bs*iR^l}>=@Ggw<5dREjxxZKO(YsjzhLdWZ&tQ9YdO{MD_-^>=@E~x5)a( zAzLi6Q{A$XX4iUCR9nawSv-|Rwdl zuMXy_J!bKh8eVzSe8zwp2h!;f>$`y}<_xzXtFz?_!rjDG_<-w9cSwJQ3Q z82S+EDd`^teLLt}U!zZnp_dB%L!f^G^m$7D-8Q{@s+MmB{jWj4O36p)$wJ=%`bR;Z zrsVIo>TL#LBG-KTnjG5H#?m5WK^FMtWO&qCT)ciUGg4#wlfg7@;SlUxQa{d zN9!{sw4RBlEqt5AnU2F_%wrkONM#;>@dJF@$&p9aZIf265nN2ztW%tYPP0z&TZUzw z;x`Jf*CtLYybcd3yk4hxH*DU8vgUfne1xCB%zEG{JO^;Bdjfoz_jcO;9M4# zde1$8vA(l6;?I%RQx4pT&GhF;>)D1d$JZk6FWCMZ_`U=13TOLsr1jhiobu;DI#6Et zHmhemcInhy6@tC-`vK`}^4Ur9JKaebGZ5VVvo9J!pei|I5Wa9T&fy^1uFD z`Ec0n=VgyMiTH5XJcm7axbNkhqi`OR%Cph2ueA*J_>RY3rt;wc{T-mwhvRar8()Si z30ER6AFc_w5^&LmrhPc)R9$*b6-nC|+r}{cBoOx;#GQz=Qz!j3csJ$pdz6d2Oz01z z?5_PaI<>zB&a6ZkIoHs-Fo$!t+2tN>pEjzObe#KFsrOEw9F*tRkv^8EIuBpUlWAai zJ_{Pl^P9Nu!nMh@K0tqsf5dv<1@{6sryLo=IV17*0C^@s_kk;WYp;ym2TXp4-ushx zna|8Eee1TaXJr2mX?hA_wf~3j4|H$7hx>n>&i%i+*l)9C`yhKj%UYC0SndB&7VDIz zUw!Ikd;d?Ly>e2^yaF4l_R0M}ANKs_VgC;}?m<2cn7Y28bVc?OtKc8beMzG`0lJ^x zJWcQaL7x4=9e+Um^VmtJ3r`Q3X6VA;{y{m$sIrpo*_9>>|-G)+(Mcn`6eboIw=w;kC>wFx z`+wkZ?*Bc7=Mg)-`>&4d|54^ZWPj;Keq+tC|CivD>xbMkI{{XchpHtRS>`Vj}hjAI$&aP0p*dW|DL$^OXxA7!c|`SCG7j{UzA zvd^Zs_?ue z4%(aIQIWukbO4fXJBqUiaGY*6~9_(fuj{U#6 zc%Gz;vhxViRjg(1q71^6QTu<)k7NJu(RA7W!%c>7OIo|iq=OSu2!oY!!;Er&u$MM z?mszs9`oSg{*#lZ&V%PE7teAJo-P+pmIn{_pPX?`^x)yMxRWQ|{*#j@-u{!5XSc^5 z6`%Q?Jdb(sJmKQ0^Wfq7fK$(M4<4Qw;pEBk;Nh7OPM(P#JUlbP$rJC)2q({2&y2|a zirzoT{yz3+T=QSfult3b0eXuEJ$tW~pAGtlJ?MM>LDSPf|DXrGUiRNoL7(EWzf&gr zXNjO+=Rr^9nG2X7p8H<-@dY0AJwiVVdY%Wp|B#j+2EEvWzE$?uPJzDMgPtw>XU9Qb z;XyBx{j;N>2R!JhvVYbOdeDQuN9YGZ|9}U*|A#vL`$2!$gT7Vv*Y<(#b>>61?5|-T z@bQm%$d|pS_3r}xaSwW`?7!^<{d1t3{WsdX7X2dEA(nGp!DIhz4d~o|tHPc8Z!=NG zl>dcW)?<&wEt@Q|KX%J{?6J6IUxN(e{q8tqe=V}TZrL%U`QJr$w_A1$X=Z(4nx7bl z>^DXB<8Ik8r1>i%yU8s(hBSXcWH*dMwo_#9cgv0;&5w%gU2fSiq`6sS3&$Z_EwZ_8 zSxK{V56xXCD@67hx2&XjG}&b$J8c}YOCZDb=@70KT+O&1z}1AS5m&tZu&A+T9Q$EW z^5fVKi;^G5epr8|BVb1+1vnDWz{jezcF|Og7{je_|itL9u_p{7? z*kRB)-)+R&O*fvc%zlU24|@T0?uV@-9nV{aZuY~T1D*R}0VN;VqcZzpUj?1}VO(Ex z?qQkzu-%|@KkP0gAKAk)`(b}|Snr434!Vh3?}s^fWk2jcpo{xqOO>wJJtyvm!IlH& zdG7ESZE5zy-V6QF`(cr_QSOI1b&tLuc8_gGQ_kEEi<0+P6OZhN-7}(iA&r@D1j= z!H>VI=Ai?l?T4KJ&mf*5%zoH()F;^wQ|~vs_rrdRIGp=o+W;qU4r{;PoYu1yII|!2 zuLyHr1nV1)_nXstHUqD4j{UF?1Lxik`x?@RbyBQ@OzU|szK6lR9Gs;;;NA~w0nY4) ztw*@_BKN~EUsvA~cJ7DKp7Hj>)`7sGw|FelH&?uR`JdyKXp zwh?shhZSQT^;TR(xC(LIg6o~Q-hqoYRB1r_VA<$4rr%$VO4}IQhS?8$FXDFZhnaGT zw;!hLj{PvkJKBDjGhKBaZQr>cR)BPv^0dDXjs39S5g%ti>=n>hp0DxF3+?AKxI6bH ze+9e#C)UP>C(k^0`ucO2GNu1H9)Vx|N>eNDuZ2n4Z`F1$q!>dfuh-64CJjbabJgcnW)X=+ore z1~X#5ZLkkIMqvLDocm7xUV&HPO!wLp{hg{I-*s~Wms<}^g1-g6Gclhq-?QfaA$9)> zWx%r5-%qgP=t-DpZKuv>j82}>58lt=nSLV9RyXf)UJiRCXJyTK7~i0K#CPTT>+!9f zx1v6TADOV5{QJO9Jxs&(7{{503+3y>66Y~~#{jZMH{MySc*LZqTc_vmpr2UtTDsSv3bv>iYWCwIV zg)qN!_Y0iO#d(t%=Zo+?3(BZ+tiJ|(x?1MrltGv>Tn~Q+-z(#M%*Z{p(jnIixszJ% zLzF|9a^F*NMfT0+LWcRike&R{!S;6_zGXoE0)d~!cMH7ApWhH1YxzHiZ<Nz&ek5dQ_}!D9Fuoo75tJS3MGtlV6LhnW*b&mU)V80=_C8PP$=`L2lH zL~O*d#M|aCYdt-^zWaK2;Qe6AWB{ke7rYltAC@B6obwN!9l>$?6zIg4T%as^B#n<# z5A?o8;6LDjcaq5BIw+j3R^cBuJ6t4|`9d_ooEimWOWpM!h z1hCJ|(4&1SruTHPEF3-+kK&yQ`G!X4++DEgGg@XLWe{ea=bY;{mW9Ko;snmuWPNx5 zeK`B8UmidnF_$jHbK^S5@>%8iB(;CL*Q_b+_E?`RMq9x1oz3%@2hXi8o;nX6%o(Hf zEcf6++M;-}Ja}$#@zhO<^|61Ci)Xn9&ng#BmIu#$;Bh`<@;SDQ-x@&M{TS@|MUQU{ zsBaa3{$bF)zEx26xR!qq^k+Tf`#+=U4WR#%2fbe8*Mi;)y0dI1daMt#FLUy|>~X## z{bQXxhdp?*J#4Y(3p%aENXs9+(%PlzH-m0@?6IdlrRj@6Px7D-^Br8+@_Nu$d(hQ8 zwxG`g-Rm9OGQOh=`cgS<136Ft@`xJK#ZdD&yVd%BC~um=y{5pma>`e$`oM!t=5 z^T15mp#R2$-Y@j8f&R*$IWNl3 z0(In*NK0Hl3()@>^tgT&pnn8(`dLKP9}judH6f*p+5!a zm7sq_{2iV{7;A0nUE}5O&(4x>Rir!K7smdsdcU#?cltUUhYa`cdmOS^SVPX5c%wRp zb2Qn171<{pvMS!!u2r(mca7cgeoJJxI%J*kjwbsLBKskStcq8BJ4Q=$m&i7_WyfHv zZ6X_R$U4(JTD+_;v~&45WLreG$RVrp`|0a0Xy+P{&2z{)(>$7;?-AK~4p|lN7|QoH zkxg^Rjy2vJMK;MHtKwa*^E;ZIGe!2*7b0!J8SiMavqbh+4p|lN80?%Pvd0{<&Ui<& z^M6Bzb>px@cC7gw7TJGx$U5U4Ex$h(*)KU{$C}?Ci0n>>tTW!x^838V{>?aK_loR? zjF^=qLY5t_hRyt(IT1J~i_T3Iyr>#ayb4X-wjUzi+nu8*{XdJTlifo2M zcC7imU1X;_WXGD{0+GGUA*^Gui?RZ`JjgtKjk=-*6*&mAR=f)x1 z2btaQKkCNy8C-vl>+f)V5!X&!PviO$F1&Y__Is>}@EO;fv2NB7ti{Uzpwm3Z)@8>& z6IMa~6S(+n9V3tRjyled|K<{nq7?i^)C5qV&$ho7SF#P-}0Ds+QPXD zQStj@_3jvXzf0c3*RKzn`OQSp2D`t616e^4H0 z1H{CScWnH0x+r-MpT7pk@=P!1w=PUy(1o)UqU1e%{_cnDR$O>D8)CS`rYT5nC;W7GZ^y8gjKEwUjx8i*-W7g@ezlu&A!RIS2Zk&*Qus(Auz8Y2wEBb9-`By6%M!n$?quev0qkP6jXA^#<_P<64i4YcSJr zU4e_d+_$5iF0A`p1^%mmuL55R?h|n(yZ9=xt}_*UQ-Qw^d?pQies}8g;~D>Q@bOIj zJHh9qVLfx71)5oRortjW8yEM$26#SK^8@vbi|rq5^yJ;)Ze%$LzrovOFuFDOoZt@6M$DZ z+XrlV&+ABw@&Q9S(B8HURa@KgfjfaaeZYQ-^Zj|AH~fk^o!_{4^s>k|E=s^30$qLM z0(#&N*4crz^vC#(3+xA(^AY$i{7|u+k8p!e&PSMbx(NF*%4W{@>2WsyOVHb4{D(x3 zdY>NW@}C5a@9w>f`v9(K@CTz04$G&VG~cxO@CU+~n5FO$x*fhkx4~y<8GMIIcAsl3 z#yR!3Za95?(T3s6m#eceRhy8x!YF=Zk+$Kn4wQ=e;$9;heii2`oJ=_KU*8Nrj_(J= zoDpA!GvZ1A73j}{{#C4N?#1;FxM+8kF6CDl@f#b|exs4JjIl4u#yJO!s~>UEw~2Lx z``f&;4f3wande-f9BWaA>iZXB`^Qjzs+_d{m_AQoo^LnH)P0_U)1HSt)@3p8(B~;2 zJ>5u;DSz7^5aquH^%ScLwY`}dDbuzuS; z&pMJk^$Snn+>qBkjx=Nby7(3FSHez}xc?D2KfaIAy*V&ai|=E+{_w54Uzx;j6YzXi ze0Krg{KmNr>YEqel{}-(pRvD-f%U10Ckm_?U0DN0ux1-d=yW82!qvyO9=Eu6(|G z1!qCNTk;f@Z>(uK^Ia-D7nASxka2&nMc3KH9=wOUuSV6`#M3^hv)prMogJEIZA(I) zAAx+ktG=!P&SJhU*ZGR~4VT%H-l#m`+0~h+X~J_cd0GOQA$|HL%eH-gKYgj_$2OxU z9cS~=C-Wh+wLjSB0?j;q0`qH;#XI|%+9wmT`zbq5%id2}+b478X`UlZnFQ!k-$N*d z-yCHA0WwI#z}$n-Qw=}NXA+L|P!H%lYl7)`pVDRgDQBMMyX-t?Yf0nmm3po`^Yl}| zb!}cXGUS_~d{p&!4d vtQ1=D_Z+P1D~snDsX7dxM{6fv9iPIQXsw->c*U?d#y< zxgK5U>r^@mCU1KQyf=a8_e$5)k=ASF{Ef}}d=tuJOqu`b>ktQ?3-tLLZ_Rt=8Q+ns z4K34Jd@uUIAFsJ~+adVk?)Kf=+m1M%0{_##RlR7751jOU<_V4$-6tm;`Gv3JiCxtb zj=(2O`;wq9-UB-^p6SpvUL8-0j(PiEmte!b+yEL@oh$#+-@*UY&IevQfSHMzx?zJ9&< zCt2_@P3CuX;Cs-HGu-5Cg@L&PsFNpkJxzjc?cbT!b2ra{mo~lUr8y0G;1Xa;NzVBD*1u z>}YB36xsXTvhptNbjMz+JKje{_Aa-qyh}TpY_rG~jzhLuWOJis_hx;0i7KPf;;j(b zYsMkFOk}6IWo2)9w0M_5W;@!}r*O4k&A1uY1Gt>;1)9EPaH>@?o;Hw;Z;`T{e&U~T zW(4BFbE;aSGVktn$h&%90v+#Mq`h0kA9=5E2y0bpJpyT^>~hl4ZyEVgp z-{e{i=2YrTK#rBv!LjAj;5Xw>9>X&JJgM+{{Mmu<^Y~6F&n)6ted@VLAF0-G4(K(U z-(MFw*Ydx>Gl+6g@A2V259QDI)w9^AdYo$+MjUz#N1to?1;9ver}I6&CxAQgaec1k zzaz|itGSlFhJ*7ifmb+t4F~W40jJh*kPejTHqQAEAblrr=Ne8e&bs3qpK})HdweHQ zUMqo9@9{zQ4uoqlH&M_0n8%oP8$S0B-E7uv%(qFWpH6_h8cUq#TH@I}g!I_Y?V^V| z_#MMm&;~KzeHiyOxYW80%9v$!g`#2I=0I}Hw@m(sZ<(BHEZRMEx&D@kv!2CUuW|B> z)hB1`AM`nxn_<7_JjUg%T(7B4IPx&)FMz%bb+80iF|J#2vCLpctmmsUPS0>%ggD*S zCZ6saXFrh2wHw6ye#Dz3^_+fyZ<9DpIsP8y=q^L9nW=KZx(#i@I{oW;_--l6)V*#K zWiyX{fODUEtcfr!Z%0~8`P=XPq5RJRZ@>2^<KYjNFX7;8DFak-!SVb}SCK5N@6XzO#)?=lSk-}x`0&imAP?AEqC;MIBxXqso* zeD||E&(fsqETv;wPY7wSTtBo`JStlj`e5}V{O)^-%8Kv0^G@r5)~fpI#tj>+>iWR? z+UCI8rX~3dS8b@#;Wbq)b=85EP;*_wy0^bQaA%-7*i>It9SqdewKP?Qs%xzkdDZoc zmo+yxHZOx@Q?P2i)!1ScHPkdW*40=k<@HsewT;ai-tM;=sx}0zb=5)8{P>kL*F6|)_Ty@)Yi#iQiOv*7St*L8xN$>MYbfY%ZKw;iKtv>q>l>@r z``0!HA7~9WRBu%1J4-*9V$~>>0a0los}v6?aikVf0b9xqD=rIaEdPS)`UM-RY8C_= zs@Bv8b!u;It*fu`mo=_K8d8wDOvv9J44M2cFKMyv4%P>&T7v$&)_fpX9Rj_$Ian16 z7B|8MZK2zm8#h#JYzk^QZ3#-H%xi6^39j|uwydJKG?3?yh70^Dz<^%Y5Hu{AEv*}} z{dG0j{-SLE2U<5Y-MTT$51jw{cle9mS6B1?n?WR?X*Z8bb1BdFR4!@rqTM`Ns&00t zy}(O_Xz+~MsEoAR8If8`o=X?^?@~24K)wd z)r4vT59S6?CxB{PyS615$_xZFi+^o>V^zpMALezVZq4#P?5}GG(ZcWWXRZr|0_&O^ zTblxPHJLeC{`r1lw9=Nk4+b?(n@=Y!%YVItM@ii*@v#Ws;mc}h4Uj8UK|N7i3D#PlihQdjAnRruz%tX z5;6W?>mqfJA7Y;#+u&`(Mpa!KJ0^37I3R1?1(AZdDH1G-1Tn~%-ljMbEQth{MS{1X zD82jl&{+DZTp9AlJp{T(mN5@zG8)S$iCpMWGIrF9Vf4=Kn1?gb=Q-w&Wju?M<1vg( zF*$jIS@x)^V=43eQOkTRgHs$6jA5Ah6PUnmJ5jB5EQTo<)i7fjY2p}W3}eQh%`mpP z#?*~nc;#_RO|y zKb|eyFf8JEICEpRUmS#|T7eT9WV3l)FR&TGiMf z_k*HYH)v_XBVx=`VN<9%Tb|eg7_=XjFbxnWGQ%GYl&NY|7Av!UB9x~+=Fy~CC-V}t z5mo5_6}zAUcs@{Xj2&Z~H7Re5H7QTEC0%*)vN8i$g}|TdbF*L~RipA$^D_+p-&L=8 z=Fi+{p3@QVdP;W|M*bKJBi~UN`Od=7g_4)0?~Clh$#)b^{-3|?kI`711i)%~#)N>^ zgSpdu1!FW{fx~0<6J;y@<>vaJH z^r`>?UTXr*BF9kbUJONQJVruHD>xSF{wa6K8!2^ND+;6*+$8th923Yj0n-k17a5GH zO1U^4Mfy!7EHW%3VHeeNO3$lS2w<(8T=fW!P~IXF%8wZJMuRKRPx#;~(ogjW73(K? zgqHE?JzklH5DSV8w_FS?Df8;q`t?3QO{Qb}CJU3cc}>k#>o!#R?aVSo2kL6+q8i1u#=r0aYW> z;fre{f9l@wQhd&5ov}Sc#OrNFnY^+(IVP`COX5~1nZIf__XJk3x+69$7u6B}Pbl|{~v$n*c%W{YYiFQ_M3wj)Y;bK|<^ zstxzmg=$wewl-G>Ei(ZV{|Yy`*9lj{fAJma}8+>j)Z!3*^e{U44jb(f9O|{w>HU-_*c+;)MVNGr8 zk7G-46kCpENAOLxDE&S%~B93BsOdKxxo~Q~vCUal%J#kE0_^>(tO=9nk z`jYR7_l}F$+2L_}$@e6VEAl1Z6B(l4pvU4R-xEF4ad~_Gd4>S8o-GocNCsF>!#@%=c1%8lQ(GrFmvPlHhNTJpis`KZS(O~+V%c6 z{n}Z4YSetlOnUwzW>(&demGbpxGvZn_0|~=8_}yZ4C%ERhK$oL!^$WKTyod_pY~?m zIHpXf2f7kD7X4UBJSvea_krs6(V=f)*+=K#dbX0daT&In-R$(6Tnz9Hl@X*tP&k;L(2Is;aMF5DK=0S`gN6uq|lY zP`{uC=ib2xJb(~~6t=Y1hguc_Z!K60J~FJW!;yn2e$C>4-(BSucq4A*`%_Zznw$#0 zJ;m=|(3I_uWZ2(;6WHuub!}rKPV+O?@Mn_R5~^y(QG^e{huWW$MGZKH&lo9M-tQL; z+Jev*g3}n05x=s23yz;_2?eWa{EcgooEpT^+}O~lSeucc(SEgc zH9@~VB+;)eTo-KdzYi~$Rl$I7_pfMtKeH55uo0atIODK7go7LFH~O1f8{|wqzg-3V zEGnhL6n;xnL|TX3I+#7YpVrhItgcf>L5gUsu9^$#(oa8Q(IxfJkvMm{3`b0IVk@rE z;#Ofey$lpx(~Sn+-CE=jLunHcv)E0;DXhXQ8c_XJYZ@O6DuGBb>mqhFC5MI*v@E|g zDSxQZkH+L@V`8bUWo0+5OJM^%=9AJbO(?##8x_*8kT?fa3A3qExR%1~W*m`8kjIPG zS8enw>V{xTOVzqyid8r@9NzA@$`P(~z)sp52{(z(cHEcV!u-k!qVKpScVW&ocyYG6 zu?Cg&9oMvm)-EWx=9YJ+SWB&UT7JLvj%%!It2Q*g3~7#{=5?rh?aQPC3ves70AnJ4D;oVV zU1dvaQ&VGeXs&;yNt9wOQLhg#i0z&;Z@;bVE>&-}s({TBkQl9XFe$38Nq}0Ui-Pi^ zARI<4NA{}q(J06^oTOWsT8G7=8qj4X;V6nOHBB+arXgK!5{{D5C8sG!filQ)J%jN} zTK$=~FV|*}0mII{$&A52m}}?AMnw!@qas$YQ3bJrwmrav0!95oK+=woHUk3@oHhV( zCie*HtTPbd)0qa&54# zj;{5#ltT>XD%W^P-C5P7g)%wzkSog}wV|phO32TSxVi~L7LI1d0at8@JdHu8P}6W; zbmNAArUgK=qEdNJ11OnQYeP84T4g26nYmU{MZk^=18P)ENZq&hz2DxYukuAD)5_T+aR^=(r!nz5Fefwe?fy!#i-_zx{l8 z0C5aHc|M$u!_ANHJRdH=z5R3N!>e#_`~3NEC+ItH-;4V}+}nUZ_J#A|ZrrV>&xdh# zy48()GSZj23;J9jCgTR z{t4p4z3>>~!~NJ#&xel@|L^C+7W8a64m;qU`g7>VeE|0z)c+sn!-q)!-{-?axYrLt zFYR;Ue7F#I|4Zk?O}LkyJRk1Ez5g`w3&U?81|IjJ|3tjF&;AYK#eEa*1Go?3eg^l{ z|AM}WuruyCxNpL}9rr%m58>YNJJ=WZbGWDD1Ej})e?DA_d-|);%lm7H7x%PtNDuU_ zIuAR6f4~ZdyKvu<5DwRZUW<9a&<>{Xo4wvGdmJ$x{z`b%|IDCxw8^Ymq zl<&}@aJUKgvv-BV1Gp!z4~KJ5&a1YC!)>@1d=hfFr++FO?!|q|cF5y?3iouB|CDDS zk2`<(&XM{he6YOiZYyEaoJl)3EZ3;nSEXL9=ox@nSNymq&qRcdALUDM+4O1A^lZ>- zaGgS(%s?3=PZs*B)VEIg{DjXXe(JLA$)8U7OzPwM!8#4R{3U!)r6z%C;E(a}>f3QX zyp@P@hrH01;=c2<=fk^5FN>wG2HO9``S2bOI@5{oEm$SUXBzIw_^6lq#ia8sJEnX# z&B_OHDflwcb~4dMY`d&>#H;c}{wtm^`JydP;YvrF>ShELZhmbC@-aPZgUPsCaneDX zlxEuS$2klFlb*>`aFY^=^e+4%+k-#_zJX z%0Ke$?>`@|L|>5n34CFfzYFN4okNf-{o(oWFv7_z@nv8Bocd`ujkRcpUEohdAEL^o z#e*L_Oz%?godI7T!d`Y527UX#AYR;)9~M3F(wkH|BWZcM(z_k}O-FS6k#uVNGJX3% z@Awh=B-&||@;nZ{kr&aIc=0jK_|ZPw*~g-f+yuVlJ0zVkdQo0rWBdofUxvQ41L5R= zhkZVss`9ZKe0#um5PXq*p#1@){WgJKc?f+p!fra#g>Uv)Iq0j;Ae?-k#N$;jL8rcc z=sN>`6`$Q6BX%1GeLMR6A@Iht8{^%Dcq=d_sPeyMlz7oD$$u351wX@>iE#3#yzCLF zU*u23Skn#uOxpXvDEh(6d@((>AC2GMDxj|&W7igBHTf0M7q6Z<+S@tkJrqZ82IAcV zy?Zd09YQ$y3)Aoyzo>STs`C%N{#VY2OIXjJ7rvNs()|qclZdf%_NnvX3g-X&!mpI; z{BDQ7@?V?}v(3BP73KGVUITh%9QskvcY$6Lhkh3HA<$VCUi#CJzO$g`#G&Vdp7=|Q zu^x2lJO#RivAK=*xH_IabbDfcwn%&>9{N}gyFkzU!};(&(xdDjU9VPSygP$*A7Z>G zF>SuJk8K}qY&|{&!+V$C8pCli&cLn&%F^4)wy^}ocZKsp`Y$r{aE6ry8 zn4?k^Xn&?>FXmLG;Ey*hQg0df23|iOK8vt7Uu0aSy*7d0+I&8|pZqR+(T3TW zvxP8+D?=iZZ&e0I{i{JI?-hyM0!!k*(3<39)bQp6u`9N&ZZt$E?_ zp+v-AObPtr^(&6?s{(R6L_Tft7oxm|%Wa}cpDJy|80vy-(;LdTx8WIXVB!(Y)s7l=SGoDHS z2g%Q0c;^8mtBAo0{^5@SrfQf#C9Vtx_}hYODXy~w`f%AY;hkS^hobxvAZea{L~kYH z4}k#!`|*cb4-w#>O5D|Nbi0ja@7F)hNKZ}5h8|k0f0kwW3J^%cb&xDvhd(WqOl0niJ8+DZvRK113Qka>PHUi}UNSRHb zNhs+AIOV144nKgs02pZ*0hSXhaVdc*iJG#M0GCE6V-a9MlkF@X7k#xtIYVGC0NS90 z0H=mb&H%nS={qBoG<11BRyDHa5GVscwmzuz)f&o`0Q!)Ah*@PbEh{M#57h+931kCU z1wj3_0ASi`@Wn%q zo0Kg8sGy9%KB1HnI3$!I=5$B^rTVM@+et}-p{cEtKqdf{90Ht2kWx-ywNTOsv;(jc z+97OHNZ}-a3Xal<`-L(ps!!p1~CfxjtScq0;!n#FrIb-8334q5&|VcDI~C3D2W6% z3B@ANDZoM2kX-Ae)p;!Zx6qGXN@3Y~2DJrM4jf_R~~n1vpMh zHkKtRa|jBODg-!2N=N|JyR-pV3O4oI2LL*(Qr7E309bp~?~G7NNJ+#OW^GC~KQ{}W zLQ)Eylv<%IC1sP7vP&ohr1Ux|gF?wC<*bu38yLouL&_H9gPA*Z9r9BMdl4wbJ!!Q7 zH3TwXR#LKYPdX?-KLP(dP1%XLM^d=}snpgcKo=>S0NB>)1;84T2sUdNKsoMH2rSLe zWx5M8Rw;mX9|HUx0+}gL3GD~KN+G|55244E-=W1i5Z?LfqwSXO=Lr>nSxvI3sS;Nw zF7-Quze**glM{5BdJ*sz)Dsj73>4B8h7=Z0zq1GkP0&J$1ckbX*$59P@~F2hM_Q}OL3hgq7RoX^Ty_NI*&O}$eb{13HkU_h)exK z_)E%8TnS7Bfeu`%@)FpAE1?sAM$hAFaHt;x%p>ckRf~&}s~dk!QVhsrIu{K-(u)kUUYHh~TSQVDSKmxepnH>`64>>|MV9%V`h6aXOGQUaXs zk&;MY2LLMSCNL~)76B_sv-Mqua3%mM=q0dJDD4C~0N4t+6?GOZNd3k?2R~ry8I7xc z3>4zpM`#l+W?&bAt+*J!qHISXAD8->dPZQiM(F@$)$>CE44ej_hULdrJ7UjGtzLYHdIrJ1N1pY9lChpApz16hpG)}KJ12_k&X4lv!5BQ4;YR1y-y20nTD#=NksVlnfD=jnbjaAp$Je902DSDVqc--K2C1MLlgy7UdTcx{ltZM92xTW_^3nNGTQ@1?0H`h94`3$%T67mF+@`0kO9`9;P;b~O z(4Ug6gp^tUWJ@N{A(TV{I{`4BLwtT>?@XD41dfVK2Z3aC;;TSWDX0NJHuccf20*2N zY&(Ra9@;pJP<1jX142;`ZKp)$5a#s0G&B}lbrS%U0#djhP1PL)b_rz*fnESq%_jsO zmvdE42`GO7MoPdx(V==10J0^L(g}d7`7q_%D-^XLa}WSkcaSn9lr03#iA*VhY_2ha zE!_{G1As~aDO{aYwkE)(NEIo80RYO@=>X0GK!Ixo$ym`N&<9FVngII=&<}x>UIN(y z>?2Shz+M6+0_-7BE)XHIGtUQ7yRKN#P;^4Kl=5veil1CzL~^9CA|52t_sYL_Epc@np*bzoHa6 zDYZiBrZz4T*fLxfU{(CefOIw@zJl-aUK&_QiE0BmimgrYi>dM9POlhW;^a4mr; zsHL`3PD(1!q^M5FkB}WtsgttWN!cQlQfk}br1S|zcU(@&IVWX`b6uc7)&(-Dt;|W` zDg(qU)!B78DSMrigHFn@P?D+5az6cM%DRB+AeTBRHBL&KlhP%WA$DB*oRs52QJv}; zCna5085AWOfNfE(^)Ww(R0rv#bP7dv#Jil7ekWznNl8ZQptf#mn+?E@r$i{Krr zv^yzWLQ95%gSaPgagD$!0wV$>!iY)f_(KX;LXx;TN1%kjDgkN;vU;2Y<0OSjBh(MtL{RGMc7$C4pfTILz z1UN>ZNr2-7HVMG>)uavqP7&BHzz~5h0fq_e5#S7gy#Vqp`JDp5?zUnc{&01>9{1G* zxFXIj`YdFu9QEEi2IhVI&nQ3oNW10x z&V(8$VTzAoUSVy=MWYW8*n^AJYafBLxX8wdiCW;uA(Ft}1Wid~vikrq#U%ue1IWfb zl|bqQ&BkXui*qWnrIC^epc{Af<06P1DL1Dx4J8$Vq^K150oasMp{V4nc2c%DDZ2nL zbKGJ`=o6ryz$pPZw@TN$nTx70MoT0ltF(NNFN)N+|UNMg&kxoM!TV6y1}rPzs8@n6C){jnPe@ z0{|oKAixJpmNZvh)l8Tr%?`!Kf+D4q6grrYQa}nHqDaXkWv5WGNjWBzWKzxw#ZO8O zj7^y#^w&Nv^HEzlDW=p;k;39;PTBkWSQSeR8%v3)-a-m%64^=#4}=TuNXm09$pFu$7QPM;4U=0`yv; z>O=xu0-@?dm~Hru3*{hzGa}PLAQcm4TXmsKrMHk$Ayes60wJN45a<9v)yV`n7l-L| znf3~h2ujjH0W1QXrIYO(W?V_f1sEYPB*0k$X9eKIEQwW@GQ$Lt0Wfoe0MrT-v%QHx zCMarq7h&rZ_E*T(!J0S%Ad^`B{MdXWrIwU@05)Z{P*nA&+pJBYFEwQpWsj3`R4Ap? zHsqvC!R8xfRFla7U~4OLQn<-yQ#yo_No_lwl!HRi&CE$*5ilM_;U=H0ZK+U_sjb{e zX%mWSnp>TeeNM_DC*_P#R0~do!R>gm0WbxsITt!9wN45PX%owlzY#RaWZbzil$4G? z1TqK|2v9;`l>nTwC2^`owk-s92(XL5K>-E`RH9d5H2d%vmQ*i5FM&1z_7m75Kp%ll z0l2T1#K#pX;KO4QA8`ou6W9YFAAtG|0)S1d96WtmX?Xmq$Gw0+I{;S80mxWe0o0%? zRKGJIQyU+X(dM0d8bt9o{xQY)0@Oka%Y!ph-zEf@7Bvp+63SlK$=55C5P@StX(BKz zKt2IWMu=nVMDqpcCBXF+md73fn*cD@8oHtN`>g|sS8@GSeG7KrY zx0kNJjFcQ16jX0t0)WX$C54Z~w(9M|mP|^wu=TSSJ|q;~+XG;#w~}H>*ROhe`p2l8 zlEN1*Y}GZwrh5A}VdJ*BkMChH)w;I_K-Ju8_YDYzkJP?XBEu(dpM`GRR-F$(Wt)^z z04fCpYK2ltU=skUP9@L<0H)IxHA74?C`tAZL%<$l2-rgmv_ys&0`?F?z#d`6yY!^yBDcw%WfKXH==irkm%B)l~La@Se@UbbSLMfv*4n8(zi%?X< z;NW9Z`kWLFJ~ri?P_n6wgO5$2Qwa^P8WRT}n-X$TIQZC{WKB8l^L zDxeca(p~`h0Mzdk0A$I^=b(^|v7;XMr35$I@of>AK>|BOW*3280Jdr_^mFE* z+{n1Lk3?8C(3ZsI{0;zI)KI;+EmI-Aco(&?OJ{Ow2y_UglE6*?Ob*w7e0@Uk6F4d| zTr2Xid$v{k5h{U90VAyeKn3a-0!bmg0V_T;Hz*0lm0l=2o z1%Sy}t+WBaf9*BN@$al!qsb=vd2j| zDwKYvfU`zh8&|I>qbL~wYzhZ%n^NhdaLge^rGR6PEpyOG;hfs0aP^upYHutJfKB1* zwM{8^Qus(@Q?@!OobTI|Lr%&Wq4Y7Qi5Qjac(MUdMp5XUXH#mO6po8FWtUJ?PJ5jc zu3p>P&N?Yvy(UHV$~gdRZL5T$wDH-^rf{c-GW(foK9t#%0Vm~@lah)7l`^X9^aHSE zxWi^^TkWK9BaW0_#-B0Hp+S@W&4}`EmXHAQd`(~;tx0JjFhYJ@^#siPD2ISQL96B+F6$i}n-O~EQ7Pyv7jTnZp*I{?UPnJxfS&0TS|-pYig z5#YRqIaR8MMZpwMl12oeM^{oJ^inmK<&yXS&BUsoc}Pv9Ha?_g3c(rxz(^H^GYy+! zmOhz4we)FIN-xtg${?!&*c2{(+ScJis!iz=iZT_Q4Q$Fep{UGF!A!%Z6v%``QOcZ@ zkdwk0jV-g+N#UcYO&NAlwj^uAcjBJ3OMtxu4hk?pfcyTqTLmnvO8lXD`%o@wazTK# zI;l-4hX`yDpq~JJ1@ghBesm9DF&1Eiws`bFJ?W9%x{W^U*0*S`rk|2K^Tlf>u!bDd6R^6oU2A{lG!(tYzToP`&L=*q{aJZ42L()g1 z*cEKb;f%nm7HNI235+$^|0}-%vHKfUUVfReoLiH|oAPy2-LR=AZSOZ0adT+6yy()M z7Pw@GzwCOTQy2OBcL80m=YC}L`W=yo4&7c{{C1q4x8j~GfBwRo7Pk5Ga&i~vagC>8jj`WsumCj`IL)!ttb{23SiGF5z&t%C1Gm*XtKuX6EU5BvnQ7h|7Z zrPs2S0iS?U@0IfP3!bk$5kD+=r53bx2zb^1DkV4B3c1p=O9`f1Q!bCLS3L?p$*ORb zJGbd9E4E+yy6{)J_;t5A4Njra`oAsw$zM?cl{)@8q`;|`-^Kp}g`a6vy6QQ13i%Y` zuIE2f__tWS-%=m=(fAa>XMQ#sKSl7vF8mC^AAKU4pB_Byw}*7Y zw~5yXzGJ72QUUsrlHWWx8>(r)>GvCqzAqI1Ox;1*#6^NH__&Qy0n^@h{B1P8Pk|_x zPekKQd*7iuI-6+PwY&bGP#lx3PFK62^O9vvw#t5_3c}WNhu{yo@b?Qo`Ne4d2Lxa1 z!fz4$As7B}!B5c@+m5$K@MSLiHwC}Pg{SW|)4#`+ua^YBmy64eAKiHs|B-0?W$FQX zvUSddPY0g;l__`AU*!RxfT!qMX{Y9S`CWoH?bqPfiJsEObYcee&F=TorC;(3-t>EA zf;XxC9Q2IV@11qo=ik9^VLq1W>Sy#g9^0Sjar`Y-rtY{THI{Wk=}EULUH#`T6@HSH z>FVE1yV(0VTZIak`ft{q4As4) znAq}KuJCWM+Fj*k`v2kQZ51kD`v1ajN8?TZ-*F%sZ~A$&K4_?>eDnX_VD#Pedz&{DP zE=)P@7xS5R(Ho~-bh+Ba&!A_tc9Hhe==9G`VnpfK42rJLZ7Tjr)>c>j-=gqSaaKn( zziuxxtv1)Z=sKl8wq5AOYE$VRDvsfT90 z+)zzDblc&CVwh~@xa?!OnD`XJ^d1~884O!-sJjT=oziNcD`gd zwIWkq<*xEF{afWG-1#--QtGmUDVG`-{#7X#qu*UF-Eqq0xT{>~J3d;w zX#cf$xtwv8i|NPiem0ulluLP>a_P9paw+(3w0_f%#cMCCQ=<7zxtM)Cce%LpdqOcx zwsyMgV9KS}g?}&X$^OddcbCgZoN~#YsQY=7+7DfzT=t(aoH_^E{^?es=rQ@y{m&$; zq&J#hj|)?=10OxU=y}vktJ763|AO>*J$Lsj{9CLYamvL#zWh=p1J7|~CWZQL`nRUH zMW@rAFWnK1H}j>gvS@stQkP=2-x-bnj^Nu?MB`0+bldZU;-73CbJ^LH`&k$MM^f%4 zU+!`*m2&Ybz3_ZMGPs_z$yM$n7by4RuSKWd^pl;gayRYq_2;7bO?#|#mAmODceu*^ zLi37ty?`URvMe(nF1sr_UeoT(ez_4a_IKy&gkqR%jkxk_?4S0>X#MZN#x2{O(eJkZ zjyU%3ciBGxJ)`x9Wv@ratL+~$?sOV^*1FPf?778-e^Tse^tRZ+YzFoKyOL8+PxHTp@bQdUC4h&k}skb2H2Wqd z-ggLpzofHJ^ziKR1niHv_iJ=KvHMx~fd3lg%dC%05yQ0ue+BU7x$=jp~;^2<~Kh?o!f-ft6^v~TIQz-)sW1ZLHT$rB;V%N-i~qfG@E=h46l?Xzw1QzNudj)Iv#-=8 z`Y(fW)}Ldpc9aLaSG?cAIPQgi7m!n+$L+VUDvq8y;F({uPt+&rc`gn=U%5sWVt&7l z!~cgk_-pZw6XP}edZxVS7Y>n_-@V|UYen{9(S51kTHw9-+eE+FPwWu>AH?DRc^v$2 zM2}hD>k~cxG+kbUuJ(Ql@LuV;19;}wtXK2JO#W)(@IR#RcwXD9`QU=2e%l0}*`wh@ zqURq)zuCu^?%SFNM^N_XOJ)DDK-A?aya0~d@;LbW;^1q5XTFSIL8heV=W+O7RrnOk z?1yGZ+(|QN&&d9Grr@Uo&-AzdlSZ5q{R;&j+O6?9!e6BD0yu6f+Qq8Xpq=vvKsN!cmuc%zkvH z==mV8ePvbvh z<{>{3{*wE&{#}yRUkcv%=VYkoF3WlZ<>gg>lHdsLRW5H;c&z73eJ&LJHv&Hu62>pi z*z>kHdfub>Mc8p`7X4Af1URq#I*e&aW?N$UAh)JK+ksn{)B`0oPV%l;LLUzi-X zAn>dwX519>SRaqW|M@uhug1ZjRQMEYMDkT8ai0TzD*jDzwU3Ly z0e%YB6O8>e74L7w(X&1dzE$*_bvAy4hQIFsuhRcn4G-y?bqC(|_phC`*0lm_Bi-G3XgG3+FgmIe?N%B zKPdcWy{=yPe-Vd&!Cdcj-UK|$(X3Y=6+JryZ~O{Mq<&h}&7n2Hb#)C3tF4SSE2Bms z@XhiXAgb2Xg{szBH`G*xs`MXxmVF_<*u9~(?FN3^y5)x2#tp$6*0k2u*W6HD-xRD` ze?v=i^$lR#&>N-d!zbWp#I*(zlsGMZ3}bwCs+T4 zsR?kS5UN^JAIyotb32q^!C~@h?(V$yN5sRR+ri4~(honyajr ztIU_HIiVlsRi@6&RBj&}TZj410#Gnw5yU-9_3@SFpyd|+*u`$M~ ziWQ5MDu^lUNNEJ#Tb5hU5^An%SXZ~UE?A?#6W@XoFUwmLi(k>WydeZ4YsiwCV5q9D z9`fsgp>ljVer;p(hI@m}Ep?3z%gS>X2de7>O@a>8)r_OoG&Y5xtHo3swwf9?kQ%fN zSN(OeUVIC$Z(O%7*lglqWvN-1=TQe@?T>2bF5TSNhKow*=JHU#$ek%ivMxSP>*^cV zRMiL8p!0jEt|nA#a+j-fr<WyBdjU3zU}JZCmQD+iqLAtRhfRbZgnN02tLvV}a_b`uYIJ`nm?F zw6t1KYg!sbxmD8`sA}G@BtOs+s%l0jSMr_}MRzVQmfo(w^l*#N+bt_!8CvpSusYP( zynJO&U}Y8mF5@`4Vu^0F#d*uttYkM@v7CM7;$_Xvjm=;PRJT#C5c2ch z6)Riv19u0TZVIdnR5u5az-1dY+vNmi|;=JGqLH;{_7-B{d+iry9~s0psEYON0iR6guP zm*gyakeqj{4CO9fQ`J&e4Fhq!Skt<8c{Px^)wNa40o2U8Pzw^PQoM{~2jx_L)szfH z5UQ?KDGDvAu5E5?Xj~MyH!nA@Wn)VyxB=zVSiOExL*qj_ID7QWepE7KX(VK zYHn>^izcIUrYx45gY4A=5nzb=J+*cQ>UD?>$Tn&?`BHjR;&yx(Ft1i0T}hca#+b!4A2%Ydk__! zCRw=z^`jhrp}nT6+>xjIn(IPAXQpm!4z>iFA4DlxO`%$pX^m6}JGCorYTHn+VOWMlhjvUhX2#r_4784Tydp2AV~VOcepfZ1W|u18%PoFn%*OJ&r68fO#%cM z&?0Tq5JiEc>~*U2NwLL!fBhTEJ<327E174Id%o2e48k|_jPe)~4Bv{f{bCyDz;B>1rh$<3Jh56=~kI-!f@AJph zvVHn-x%hfX!tYQquD8Wy{mPI z?b>)+?lwysRi7#HS;9B?3!<{SOw_?`&+Rb&!kZ+#DyYF#VR|rk{#yw>K?nu{*{;NC z`s|=!(`(o?F>WV=9I@LJkcOyvnBI@yz#q@>~Moy)lT5bM@dC(b#yic7@Ch z|94BW$&r2Xfm}`2(FCH7<@nqq0@M$~fZjeSaLAyp=jDZq*XAg`+obQdh`nh-6Kb6B z#I4YxCD=~yZ{nIOH?epnG&O$48-XLj#mdi}a87)Yde+b}mfdCZG_Dcau*Aq?Q^Tm1 zk&cQ?NJUhe5}&Oin)34pO#jH5{+IFA29thdLA-9ws2f;jZ1yvw@=%;2Y;$*N4t;Y` zVMYpuL#tI}365*TVg$n$q_E=gukc&Vv#RcmU~@*$;^S6!q@jgP&Iv7I{cP;JP3wOV z^NQ_5@al5Jp}8J@1C)Pe&E!LrHjZdP6H?k`L>zBH z>^i$#ajntA;RioV!dG?K| z@pKS?dOx_k>^5Agxpp%T8`^J- zg77@+v+b6kCqn8Jtj@96rMY!n8f=5)@Enb6rd4887g~4V;2=+t4!ldPcyU*ywIl1w zJApiPOOa&Nmau(rae`gkW(O|51DrA&2ETstX7`K-?i9 z20+K+henT$xr*0SYH9==P>w1LE12LCu$UFf4ZHBObi3qO+o0CKtvp9*xK}dwf zMA}~sY5-Sf<@Iq^R16)b0l=czlYvm-C5$1TVL!uyi`mtBSKTm4svveIo;<2&2_exQ z2nD)SLtzkl=@9BophZzyvmc_JMFoBIWn=PYgU35c`83V)M6(#(sCVj_XRBwtpHWS# zNUb28BV!72K5!1$!_I&1<}d+7^%@qJ7YX}RjaXwuEFcU@QJsa4$E@!|hCNh+4Z&k1VKL#t4=#eGIbAGH ze@}|iXr$*sp3lj-EaPiY6xaww-*u|K+EP6xs$XzY@5dus)>ND4Xo=}57b&U0R&}JV zuS7TNNA_aM|HY4Wl&jsJUy+gW1cF4!H8QqWJV4xydS(htDsDoOGu{YXC&eJ9lb1H< zkdG@KX8;TEJKLu`erGD|5*ZpE(5mPowMtp)&07sc!kw~^AETxes%W>+q89AHR>e-Y zHY!%Q%{*KaHUUC;d52)awrHVQn|5kg@ie&Bk5-`z-xRtb@5L#EV{*8`=1s&xwFwlF zsm2bsy8;YYdp}*!M;1SjENG3=`e-a49!Ow^<)A>r&i4K>U`bk79f=zRcPZW0cOHmhwG59Qe#gqNV{5 zQH4Q5fP`qqPBbd0s|__Ea1j*(@{lW)0E1wCFb090X#BolhuP+79_hHc^lTtR1h}ObeYvp zzyRcU8fCS8?dFPEU11i+V~p;Q@+FXoZ}jgxN)uHXb`i)QG3}DDpk5!v#{Tz~E-RIP z7Vw-P*(hHquw8c4F;R6?&R7?6UKaUM;H+Z8gIfb@Ee#lD50b-~GdrG`k_7Yi0a1lK zS<*t={jJp4vw4XwvV^uCpsY(NZ}by=tyXRa z!|ye-!J|^*yOJTc7{fdHp1E^l&{n4Fm^#=`+jTt{(w7^!FW8KSo1#vKSb14w z$uLWhpC1g<8*_yeSZZz(jG=cJe6{Kvz!(hiIzmby;G3c{ei#hh&&YUZT2E6EEtr+* zj`M7V;R?)!e}+t!kb^D5V7S6}Hblsey>M)fe{-hCVeBz8J)XJup4gxCCj1=t_(^rs zP2Z2GCH;piblKy6{7!GW*Yk6~!e{)%rRlHlQPlFiJ&Z)p(-?Zb5ywCI^6)R!EB*Su zMJ@IHxAL^CRXw7Y_d_UDE zrR>lD4^)#ZR6p942;nLx9YyEY@?U76Baqr(&zWj@qaAIj{j~fV_4w&d(_haaYxzU- z{~LXYe>(qrD+w)sgEsf-kM|uKNq4pX*S5cwpIZ4T-;{10=RfG{&ac0F)$*@scQ5U) z<$uxW_Sg4^YWdHe{%Aifsk7T(e=pmV?&SE~^t1J!pflC!`t^LQmVeR)`+UFu&+Pmo z+pdN7|Fu@wl4zw%OFCQHn}XZFdMgXpbERDA^mFffEaIkb^gRAhp2RWe0sVGC=~uh{ WDe4c+|Ls&p{rhLqU;kCQ_5OdRM!_cl diff --git a/scripts/restart_modem.sh b/scripts/restart_modem.sh deleted file mode 100755 index fac54b32ff..0000000000 --- a/scripts/restart_modem.sh +++ /dev/null @@ -1,2 +0,0 @@ -#!/usr/bin/bash -echo "restart" > /sys/kernel/debug/msm_subsys/modem diff --git a/scripts/throttling.sh b/scripts/throttling.sh deleted file mode 100755 index d100c5f5ab..0000000000 --- a/scripts/throttling.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/data/data/com.termux/files/usr/bin/bash -watch -n1 ' - cat /sys/kernel/debug/clk/pwrcl_clk/measure - cat /sys/kernel/debug/clk/perfcl_clk/measure - cat /sys/devices/system/cpu/cpu*/cpufreq/scaling_cur_freq - cat /sys/class/kgsl/kgsl-3d0/gpuclk - echo - echo -n "CPU0 " ; cat /sys/devices/virtual/thermal/thermal_zone5/temp - echo -n "CPU1 " ; cat /sys/devices/virtual/thermal/thermal_zone7/temp - echo -n "CPU2 " ; cat /sys/devices/virtual/thermal/thermal_zone10/temp - echo -n "CPU3 " ; cat /sys/devices/virtual/thermal/thermal_zone12/temp - echo -n "MEM " ; cat /sys/devices/virtual/thermal/thermal_zone2/temp - echo -n "GPU " ; cat /sys/devices/virtual/thermal/thermal_zone16/temp - echo -n "BAT " ; cat /sys/devices/virtual/thermal/thermal_zone29/temp -' - diff --git a/scripts/waste b/scripts/waste deleted file mode 100755 index e3154ab01f1be61991bcfb2eb99229c5f476b3e5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8608 zcmeHMeQ;FO6+gR=k0gKu3=%4AHhkCwWq0$r8?Cy#m_%r@U`!D^Q(oTgK9U{w%iTpt z`4B~?{LxOcilfu%SgQY!INQlMV*8({tz+%9gM!p)83@45G#d-t){jy9{s0-PlHEf8m)t0P`faO75zLE;4ul;FD( zmckt5XK9#T?$rsF>gl+snrVr^C8VSWRsopk5&<)13yIDaWiyf9c{<7z%5|Rf$X3?^ zop-G$q$foCqil!JBbM}fgkF!(V_GicnR5TAZ}e1(ax;A%%P29`#sc{VKF)-xy|0>t znb3uLRL70_$Nl8-bf){$88zk%M&izBB)&sUH8)b*)Q>0eAvs?>oJvH(Ky#6*YY8Ix z#;K{n)!682_{RF=H#8Nc_{_&gOgH8V6O9GQ(pZwekULYK%J88?{o+RhzQ#+!mU(>` z)g-tXz-~kU)*!pM5Yo8%BKYk^@XjK*S_HQh!Iu`neMN8@=b7x^S_Fq^Bp7m}6A+3f zLObMMHIs?NREVjuw3>mK5=9u&QB_SsG8KtuwnH-0mr|9m9Kv@-1zDyV&% zWGSa32Hdz`95vu#3)fVJ4LI*nRPZ|kF1o78A2;B->lWS@f5RiMQar@jcc-9J}F?EA4q4tKr)5 z_B@Ww@Wy<59xS~t*jH2rMx+CGe=-m9xa|-7FSqAELjChn)zJ7sq!Sa*c>!Jps5*UI zl22n@10`>)$fE2CKad;@jYuU!=O!kWP8^ip`*PF#!7n6Od-b7tgYXYXR9##6$j<%V zXD+TPi;eGDFgU(m%8neAaw7+=_*n3PT#W^~k6vGYvgG4^PhVUQ*|m|ru}c!v@2LLZ z7aJ|}hSo-E#x5X!URqW^B2}#&Mw>2R8#rGBaQqI$Z(jQnVk6S5`W#ZpDyKl*lb8Rd305L%&!UjFy_lWaJB*S zu7H1mKX>?S6XxpzZ7bI2J~->fd}E-i^S)f=xfaYfVLh$6htJ)Gc@OHg<^0$doN5WY zg>|>BXwSi^m4Pm;zEy#fntpv?izeR?cpGJEABQZQY7X2!zV+ntQ?~^+T1v7n=Oqzv+eHz77AEm>Ro#lDj`k0)yHMjK{BeiVJS zcHiEoD=ejd`jr*3ug`%;zAr&H`sqO4+4+jU$Cf31^6QWA>9<0DG1hes}TGrn z?Ol?3U-%RswgLKgUh^&MvHi5R$F`$Zv5lhqF|?sdT5{<;wttDn80ATC6!XuXzHM}# zW6?eOes;u*A00b?b?ljheNFgIe9B-=qoaPi9oDV0>p990(&=}m?Zyq1H^%?d|H%=U z5Q&Yy5l^uOB{SWn!(bPbC0r2={ucHML!!ldJ~D>sG3gfOodcOC=qjJ5{YQ2Pr+lQuHWdYb2kK) zU~|11ayK^D*EM*W++mleA>>j$L6;H?HZ^eRY$V@o)Mtf#KQ-RurEg%o#Fvw~Gm_O7F2OQ+tK^rP`wJgu1f=(5*jl-{(ntF@!m z_h75+ak-p$*ifRiH*^MxR=ZeVMqvp-z6U78CE)d0h|ii_r-k@z;PqLE&jDV?h4@@x z|1QK!fY(JKUJAVa3h^@Fby|qe1NPfOyx2K;0oZvXF(^oI6R@8eU_2)+1oqcLyd2n{ z3-LwJBmBP*Ukto272?y+?NlxS?^aXNv~SFU&nBi2Jy)%f>GOM=z>_9_a0}dJ!s+m8 zG587J4{Z_hcbMdR1a9`9h`?8yG2W zz#Ff|13ahE>3;G{#I1PGQX@VH_Y3)>NN2KNAOGoorQ5#%Tqb|h?VoPXu(0QO{t$_F zkNwAXZvv0W-}LcZ2=|+C-JWvTYQm|Rnfi4SaSQsJ*`Ln{{6q1bC4EYtYwzjn@e1NI z-Q&EZ;qxc&Ig(<2=t_7d`Ogq9$9t|yyVlU;>y{$&s|dHwhol%!z8m;n5&2HU7a8_} z6463flb`Yv#%09G9x&OngX*zP;Vi#f$eZmyK=N2miKvI=pVIItKWF@~s0U2#z9{M` zH`Q|#@x|!R>{t99_zmGWK6}OZaQt>mlZR>P&xp^|-%~~8&m+Fbuz#}smqk71aky5b zo-kT6)4Z4B{xXxF+*$;87Qw+8+!=|6gNckY6H7WnsZ211vBkRJcDJ%!aU@`M*x`bB zc!#XX$?=`BpqkPE5t%?dkx^w4kI0d*8qerZSji}QPK}54OkBY`Noqswjl>-xs=SU~ z_4I0>S0lZeVD)ZnRZeG=R7Q?rFax_3ye=n=-Ka6mW^7=c+l?Vd16nNK_i(`1xnVuX z?H!x^z7Ba)Tib)J-Ez0j-_a^#4f;K(*Q?!G7G8rgs9li?Mi$qfavydws;1;!DJ7Z2 zL72KGos`_%)w&_Dps ztMwm>-NSPGsy62OZ7*Z;3zBima+CMJ0x7sjo|Kxp4i*qN(*3cF5=5Fw>9mh? zc+sq;lHed0ad610yNIJVzSGgCr2D`T?vG;?I?bd&D`Dp{GBTE>)TlxVBA1M2z=4<3 z_)aCX&O4GRmF}ixC6!Y8!C}nPr8VPNhZ2i~u(bp#<17J%&oT1eZzIup5tsB-ILh&W zpmxzq9=;$8;O&(;1d|j@OymMdM^YwaxYm7-E>Av1EOY>zVclL2jS*x&OO_zF)|3 z{Lhrn^`uYV0ki&I#K zgI$P<2H4L8I_W>m{}D6PzKa2-Lcfs;4T)JJ<+(SAfoGA /sys/devices/soc/spm-regulator-10/regulator/regulator.56/99e8000.cpr3-ctrl-vdd/driver/unbind") -os.system("echo 1 > /sys/kernel/debug/regulator/pm8994_s11/enable") - -if len(sys.argv) > 1: - i = int(sys.argv[1]) - os.system("echo %d %d > /sys/kernel/debug/regulator/pm8994_s11/voltage" % (i,i)) - os.system("cat /sys/kernel/debug/regulator/pm8994_s11/voltage") -else: - for i in range(900000, 465000, -10000): - print("setting voltage to",i) - os.system("echo %d %d > /sys/kernel/debug/regulator/pm8994_s11/voltage" % (i,i)) - os.system("cat /sys/kernel/debug/regulator/pm8994_s11/voltage") - time.sleep(1) - diff --git a/selfdrive/debug/internal/sensor_test_bootloop.py b/selfdrive/debug/internal/sensor_test_bootloop.py deleted file mode 100755 index 36eb112e44..0000000000 --- a/selfdrive/debug/internal/sensor_test_bootloop.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/python3 -import sys -import os -import stat -import subprocess -import json -from common.text_window import TextWindow -import time - -# Required for sensord not to bus-error on startup -# commaai/cereal#22 -try: - os.mkdir("/dev/shm") -except FileExistsError: - pass -except PermissionError: - print("WARNING: failed to make /dev/shm") - -try: - with open('/tmp/sensor-test-results.json') as infile: - data = json.load(infile) -except Exception: - data = {'sensor-pass': 0, 'sensor-fail': 0} - -STARTUP_SCRIPT = "/data/data/com.termux/files/continue.sh" -try: - with open(STARTUP_SCRIPT, 'w') as startup_script: - startup_script.write("#!/usr/bin/bash\n\n/data/openpilot/selfdrive/debug/internal/sensor_test_bootloop.py\n") - os.chmod(STARTUP_SCRIPT, stat.S_IRWXU) -except Exception: - print("Failed to install new startup script -- aborting") - sys.exit(-1) - -sensord_env = {**os.environ, 'SENSOR_TEST': '1'} -process = subprocess.run("./sensord", cwd="/data/openpilot/selfdrive/sensord", env=sensord_env) # pylint: disable=subprocess-run-check - -if process.returncode == 40: - text = "Current run: SUCCESS\n" - data['sensor-pass'] += 1 -else: - text = "Current run: FAIL\n" - data['sensor-fail'] += 1 - - timestr = str(int(time.time())) - with open('/tmp/dmesg-' + timestr + '.log', 'w') as dmesg_out: - subprocess.call('dmesg', stdout=dmesg_out, shell=False) - with open("/tmp/logcat-" + timestr + '.log', 'w') as logcat_out: - subprocess.call(['logcat', '-d'], stdout=logcat_out, shell=False) - -text += "Sensor pass history: " + str(data['sensor-pass']) + "\n" -text += "Sensor fail history: " + str(data['sensor-fail']) + "\n" - -print(text) - -with open('/tmp/sensor-test-results.json', 'w') as outfile: - json.dump(data, outfile, indent=4) - -with TextWindow(text) as status: - for _ in range(100): - if status.get_status() == 1: - with open(STARTUP_SCRIPT, 'w') as startup_script: - startup_script.write("#!/usr/bin/bash\n\ncd /data/openpilot\nexec ./launch_openpilot.sh\n") - os.chmod(STARTUP_SCRIPT, stat.S_IRWXU) - break - time.sleep(0.1) - -subprocess.Popen("reboot") From 95fa6b1df86b62d98e14319f5bd5cbb1621214a2 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 11:47:14 +0200 Subject: [PATCH 044/391] camerad: get embedded statistics and data by embedding in pixel data (#24353) * camerad: AR0231 read embedded data and statistics * reorder * remove unrelated camera config --- selfdrive/camerad/cameras/camera_common.cc | 6 +- selfdrive/camerad/cameras/camera_common.h | 8 +- selfdrive/camerad/cameras/camera_qcom2.cc | 133 ++++++++++++++++++--- selfdrive/camerad/cameras/camera_qcom2.h | 9 ++ selfdrive/camerad/cameras/camera_replay.cc | 6 +- selfdrive/camerad/cameras/real_debayer.cl | 2 +- selfdrive/camerad/cameras/sensor2_i2c.h | 20 ++-- 7 files changed, 150 insertions(+), 34 deletions(-) diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 77b0548873..676e740811 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -36,10 +36,10 @@ public: hdr_ = ci->hdr; snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero " - "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d " + "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d " "-DBAYER_FLIP=%d -DHDR=%d -DCAM_NUM=%d", - ci->frame_width, ci->frame_height, ci->frame_stride, + ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, b->rgb_width, b->rgb_height, b->rgb_stride, ci->bayer_flip, ci->hdr, s->camera_num); const char *cl_file = "cameras/real_debayer.cl"; @@ -81,7 +81,7 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, frame_buf_count = frame_cnt; // RAW frame - const int frame_size = ci->frame_height * ci->frame_stride; + const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; camera_bufs = std::make_unique(frame_buf_count); camera_bufs_metadata = std::make_unique(frame_buf_count); diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 9c7bf6b034..8c836e0bb8 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -52,11 +52,15 @@ const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; typedef void (*release_cb)(void *cookie, int buf_idx); typedef struct CameraInfo { - int frame_width, frame_height; - int frame_stride; + uint32_t frame_width, frame_height; + uint32_t frame_stride; bool bayer; int bayer_flip; bool hdr; + uint32_t frame_offset = 0; + uint32_t extra_height = 0; + int registers_offset = -1; + int stats_offset = -1; } CameraInfo; typedef struct FrameMetadata { diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index 7120bf9576..ce9b5663d8 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -31,6 +31,9 @@ const size_t FRAME_WIDTH = 1928; const size_t FRAME_HEIGHT = 1208; const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) +const size_t AR0231_REGISTERS_HEIGHT = 2; +const size_t AR0231_STATS_HEIGHT = 2; + const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py CameraInfo cameras_supported[CAMERA_ID_MAX] = { @@ -38,17 +41,24 @@ CameraInfo cameras_supported[CAMERA_ID_MAX] = { .frame_width = FRAME_WIDTH, .frame_height = FRAME_HEIGHT, .frame_stride = FRAME_STRIDE, + .extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT, + + .registers_offset = 0, + .frame_offset = AR0231_REGISTERS_HEIGHT, + .stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT, + .bayer = true, .bayer_flip = 1, - .hdr = false + .hdr = false, }, [CAMERA_ID_IMX390] = { .frame_width = FRAME_WIDTH, .frame_height = FRAME_HEIGHT, .frame_stride = FRAME_STRIDE, + .bayer = true, .bayer_flip = 1, - .hdr = false + .hdr = false, }, }; @@ -509,10 +519,10 @@ void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int b if (io_mem_handle != 0) { io_cfg[0].mem_handle[0] = io_mem_handle; io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, - .plane_stride = FRAME_STRIDE, - .slice_height = FRAME_HEIGHT, + .width = ci.frame_width, + .height = ci.frame_height + ci.extra_height, + .plane_stride = ci.frame_stride, + .slice_height = ci.frame_height + ci.extra_height, .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) .meta_size = 0x0, .meta_offset = 0x0, @@ -682,23 +692,23 @@ void CameraState::camera_open() { .lane_cfg = 0x3210, .vc = 0x0, - .dt = 0x2C, // CSI_RAW12 + .dt = 0x12, // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead .format = CAM_FORMAT_MIPI_RAW_12, .test_pattern = 0x2, // 0x3? .usage_type = 0x0, .left_start = 0, - .left_stop = FRAME_WIDTH - 1, - .left_width = FRAME_WIDTH, + .left_stop = ci.frame_width - 1, + .left_width = ci.frame_width, .right_start = 0, - .right_stop = FRAME_WIDTH - 1, - .right_width = FRAME_WIDTH, + .right_stop = ci.frame_width - 1, + .right_width = ci.frame_width, .line_start = 0, - .line_stop = FRAME_HEIGHT - 1, - .height = FRAME_HEIGHT, + .line_stop = ci.frame_height + ci.extra_height - 1, + .height = ci.frame_height + ci.extra_height, .pixel_clk = 0x0, .batch_size = 0x0, @@ -710,8 +720,8 @@ void CameraState::camera_open() { .data[0] = (struct cam_isp_out_port_info){ .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, .format = CAM_FORMAT_MIPI_RAW_12, - .width = FRAME_WIDTH, - .height = FRAME_HEIGHT, + .width = ci.frame_width, + .height = ci.frame_height + ci.extra_height, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }, }; @@ -935,6 +945,70 @@ void cameras_close(MultiCameraState *s) { delete s->pm; } +std::map> CameraState::ar0231_build_register_lut(uint8_t *data) { + // This function builds a lookup table from register address, to a pair of indices in the + // buffer where to read this address. The buffer contains padding bytes, + // as well as markers to indicate the type of the next byte. + // + // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. + // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional + // for contigous ranges. See page 27-29 of the AR0231 Developer guide for more information. + + int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; + auto get_next_idx = [](int cur_idx) { + return (cur_idx % 3 == 1) ? cur_idx + 2 : cur_idx + 1; // Every third byte is padding + }; + + std::map> registers; + for (int register_row = 0; register_row < 2; register_row++) { + uint8_t *registers_raw = data + ci.frame_stride * register_row; + assert(registers_raw[0] == 0x0a); // Start of line + + int value_tag_count = 0; + int first_val_idx = 0; + uint16_t cur_addr = 0; + + for (int i = 1; i <= max_i[register_row]; i = get_next_idx(get_next_idx(i))) { + int val_idx = get_next_idx(i); + + uint8_t tag = registers_raw[i]; + uint16_t val = registers_raw[val_idx]; + + if (tag == 0xAA) { // Register MSB tag + cur_addr = val << 8; + } else if (tag == 0xA5) { // Register LSB tag + cur_addr |= val; + cur_addr -= 2; // Next value tag will increment address again + } else if (tag == 0x5A) { // Value tag + + // First tag + if (value_tag_count % 2 == 0) { + cur_addr += 2; + first_val_idx = val_idx; + } else { + registers[cur_addr] = std::make_pair(first_val_idx + ci.frame_stride * register_row, val_idx + ci.frame_stride * register_row); + } + + value_tag_count++; + } + } + } + return registers; +} + +std::map CameraState::ar0231_parse_registers(uint8_t *data, std::initializer_list addrs) { + if (ar0231_register_lut.empty()) { + ar0231_register_lut = ar0231_build_register_lut(data); + } + + std::map registers; + for (uint16_t addr : addrs) { + auto offset = ar0231_register_lut[addr]; + registers[addr] = ((uint16_t)data[offset.first] << 8) | data[offset.second]; + } + return registers; +} + void CameraState::handle_camera_event(void *evdat) { if (!enabled) return; struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; @@ -1114,6 +1188,25 @@ void camera_autoexposure(CameraState *s, float grey_frac) { s->set_camera_exposure(grey_frac); } +static float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { + // See AR0231 Developer Guide - page 36 + float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); + float t0 = 55.0 - slope * (float)calib2; + return t0 + slope * (float)data_reg; +} + +static void ar0231_process_registers(MultiCameraState *s, CameraState *c, cereal::FrameData::Builder &framed){ + uint8_t *data = (uint8_t*)c->buf.cur_camera_buf->addr + c->ci.registers_offset; + auto registers = c->ar0231_parse_registers(data, {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}); + + uint32_t frame_id = ((uint32_t)registers[0x2000] << 16) | registers[0x2002]; + framed.setFrameIdSensor(frame_id); + + float temp_0 = ar0231_parse_temp_sensor(registers[0x30c6], registers[0x30c8], registers[0x20b0]); + float temp_1 = ar0231_parse_temp_sensor(registers[0x30ca], registers[0x30cc], registers[0x20b2]); + framed.setTemperaturesC({temp_0, temp_1}); +} + static void driver_cam_auto_exposure(CameraState *c, SubMaster &sm) { struct ExpRect {int x1, x2, x_skip, y1, y2, y_skip;}; const CameraBuf *b = &c->buf; @@ -1132,10 +1225,12 @@ static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) if (env_send_driver) { framed.setImage(get_frame_image(&c->buf)); } + if (c->camera_id == CAMERA_ID_AR0231) { + ar0231_process_registers(s, c, framed); + } s->pm->send("driverCameraState", msg); } -// called by processing_thread void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { const CameraBuf *b = &c->buf; @@ -1152,6 +1247,11 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { framed.setTransform(b->yuv_transform.v); LOGT(c->buf.cur_frame_data.frame_id, "%s: Transformed", "RoadCamera"); } + + if (c->camera_id == CAMERA_ID_AR0231) { + ar0231_process_registers(s, c, framed); + } + s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); @@ -1221,3 +1321,4 @@ void cameras_run(MultiCameraState *s) { cameras_close(s); } + diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h index a7c64c0665..e0553f000e 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.h +++ b/selfdrive/camerad/cameras/camera_qcom2.h @@ -1,6 +1,8 @@ #pragma once #include +#include +#include #include @@ -56,6 +58,8 @@ public: void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v, int camera_id, int camera_num, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType rgb_type, VisionStreamType yuv_type, bool enabled); void camera_close(); + std::map ar0231_parse_registers(uint8_t *data, std::initializer_list addrs); + int32_t session_handle; int32_t sensor_dev_handle; int32_t isp_dev_handle; @@ -75,6 +79,7 @@ public: CameraBuf buf; MemoryManager mm; + private: void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); void enqueue_req_multi(int start, int n, bool dp); @@ -84,6 +89,10 @@ private: int sensors_init(); void sensors_poke(int request_id); void sensors_i2c(struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); + + // Register parsing + std::map> ar0231_register_lut; + std::map> ar0231_build_register_lut(uint8_t *data); }; typedef struct MultiCameraState { diff --git a/selfdrive/camerad/cameras/camera_replay.cc b/selfdrive/camerad/cameras/camera_replay.cc index a9983fe23e..05bdfb9236 100644 --- a/selfdrive/camerad/cameras/camera_replay.cc +++ b/selfdrive/camerad/cameras/camera_replay.cc @@ -30,9 +30,9 @@ void camera_init(VisionIpcServer *v, CameraState *s, int camera_id, unsigned int } CameraInfo ci = { - .frame_width = s->frame->width, - .frame_height = s->frame->height, - .frame_stride = s->frame->width * 3, + .frame_width = (uint32_t)s->frame->width, + .frame_height = (uint32_t)s->frame->height, + .frame_stride = (uint32_t)s->frame->width * 3, }; s->ci = ci; s->camera_num = camera_id; diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 50a7846213..783abaabb4 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -42,7 +42,7 @@ half3 color_correct(half3 rgb) { inline half val_from_10(const uchar * source, int gx, int gy, half black_level) { // parse 12bit - int start = gy * FRAME_STRIDE + (3 * (gx / 2)); + int start = gy * FRAME_STRIDE + (3 * (gx / 2)) + (FRAME_STRIDE * FRAME_OFFSET); int offset = gx % 2; uint major = (uint)source[start + offset] << 4; uint minor = (source[start + 2] >> (4 * offset)) & 0xf; diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index e85223243f..650c17cdfa 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -7,7 +7,7 @@ struct i2c_random_wr_payload init_array_imx390[] = { {0x2008, 0xd0}, {0x2009, 0x07}, {0x200a, 0x00}, // MODE_VMAX = time between frames {0x200C, 0xe4}, {0x200D, 0x0c}, // MODE_HMAX - // crop + // crop {0x3410, 0x88}, {0x3411, 0x7}, // CROP_H_SIZE {0x3418, 0xb8}, {0x3419, 0x4}, // CROP_V_SIZE {0x0078, 1}, {0x03c0, 1}, @@ -67,7 +67,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x30A6, 0x0001}, // Y_ODD_INC_ {0x3402, 0x0788}, // X_OUTPUT_CONTROL {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL - {0x3064, 0x1802}, // SMIA_TEST + {0x3064, 0x1982}, // SMIA_TEST {0x30BA, 0x11F2}, // DIGITAL_CTRL // Enable external trigger and disable GPIO outputs @@ -83,10 +83,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { // Readout Settings {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 - {0x3342, 0x122C}, // MIPI_F1_PDT_EDT - {0x3346, 0x122C}, // MIPI_F2_PDT_EDT - {0x334A, 0x122C}, // MIPI_F3_PDT_EDT - {0x334E, 0x122C}, // MIPI_F4_PDT_EDT + {0x3342, 0x1212}, // MIPI_F1_PDT_EDT + {0x3346, 0x1212}, // MIPI_F2_PDT_EDT + {0x334A, 0x1212}, // MIPI_F3_PDT_EDT + {0x334E, 0x1212}, // MIPI_F4_PDT_EDT {0x3344, 0x0011}, // MIPI_F1_VDT_VC {0x3348, 0x0111}, // MIPI_F2_VDT_VC {0x334C, 0x0211}, // MIPI_F3_VDT_VC @@ -101,6 +101,10 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x3370, 0x03B1}, // DBLC {0x3044, 0x0400}, // DARK_CONTROL + // Enable temperature sensor + {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG + {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG + // Enable dead pixel correction using // the 1D line correction scheme {0x31E0, 0x0003}, @@ -114,9 +118,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = { {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x08CB}, // FINE_INTEGRATION_TIME2 - {0x321E, 0x08CB}, // FINE_INTEGRATION_TIME3 - {0x321E, 0x0894}, // FINE_INTEGRATION_TIME4 + {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? {0x33DA, 0x0000}, // COMPANDING From df8f024e19de2d7a528b5921f73895f2078cf03a Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Fri, 6 May 2022 11:47:58 +0200 Subject: [PATCH 045/391] uploader: size limit for automatic uploading of qlogs/qcams (#24403) * uploader: size limit for automatic uploading of qlogs/qcams * move check to add logging * use constant * mark as uploaded Co-authored-by: Willem Melching --- selfdrive/loggerd/uploader.py | 34 ++++++++++++++++++---------------- 1 file changed, 18 insertions(+), 16 deletions(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 50557fffaa..87988171fb 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -23,6 +23,8 @@ NetworkType = log.DeviceState.NetworkType UPLOAD_ATTR_NAME = 'user.upload' UPLOAD_ATTR_VALUE = b'1' +UPLOAD_QLOG_QCAM_MAX_SIZE = 1e7 # 10 MB + allow_sleep = bool(os.getenv("UPLOADER_SLEEP", "1")) force_wifi = os.getenv("FORCEWIFI") is not None fake_upload = os.getenv("FAKEUPLOAD") is not None @@ -121,11 +123,11 @@ class Uploader(): for name, key, fn in upload_files: if any(f in fn for f in self.immediate_folders): - return (key, fn) + return (name, key, fn) for name, key, fn in upload_files: if name in self.immediate_priority: - return (key, fn) + return (name, key, fn) return None @@ -172,7 +174,7 @@ class Uploader(): return self.last_resp - def upload(self, key, fn, network_type, metered): + def upload(self, name, key, fn, network_type, metered): try: sz = os.path.getsize(fn) except OSError: @@ -182,22 +184,15 @@ class Uploader(): cloudlog.event("upload_start", key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) if sz == 0: - try: - # tag files of 0 size as uploaded - setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) - except OSError: - cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + # tag files of 0 size as uploaded + success = True + elif name in self.immediate_priority and sz > UPLOAD_QLOG_QCAM_MAX_SIZE: + cloudlog.event("uploader_too_large", key=key, fn=fn, sz=sz) success = True else: start_time = time.monotonic() stat = self.normal_upload(key, fn) if stat is not None and stat.status_code in (200, 201, 401, 403, 412): - try: - # tag file as uploaded - setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) - except OSError: - cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) - self.last_filename = fn self.last_time = time.monotonic() - start_time self.last_speed = (sz / 1e6) / self.last_time @@ -207,6 +202,13 @@ class Uploader(): success = False cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, network_type=network_type, metered=metered) + if success: + # tag file as uploaded + try: + setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) + except OSError: + cloudlog.event("uploader_setxattr_failed", exc=self.last_exc, key=key, fn=fn, sz=sz) + return success def get_msg(self): @@ -258,13 +260,13 @@ def uploader_fn(exit_event): time.sleep(60 if offroad else 5) continue - key, fn = d + name, key, fn = d # qlogs and bootlogs need to be compressed before uploading if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.bz2')): key += ".bz2" - success = uploader.upload(key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) + success = uploader.upload(name, key, fn, sm['deviceState'].networkType.raw, sm['deviceState'].networkMetered) if success: backoff = 0.1 elif allow_sleep: From b64fe6e339c8b8b3f5016a9c58b553c91abc5bdf Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 04:41:14 -0700 Subject: [PATCH 046/391] Laikad: the basics for ublox msg processing (#24359) * Add laikad that receives ublox messages and publishes corrected measurements and position fix * types * cleanup * laikad version 1 with uncorrected measurements * push * Fix glonass frequency and delete redundant test * Update after cereal and cleanup * Add test, fix laikad and remove process replay for now * update laika * add hatanaka to packages. Used to decompress orbit data * Fix pip --- Pipfile | 1 + Pipfile.lock | 63 ++++++++++++++++++- laika_repo | 2 +- selfdrive/locationd/laikad.py | 84 +++++++++++++++++++++++++ selfdrive/locationd/test/test_laikad.py | 23 +++++++ 5 files changed, 170 insertions(+), 3 deletions(-) create mode 100755 selfdrive/locationd/laikad.py create mode 100755 selfdrive/locationd/test/test_laikad.py diff --git a/Pipfile b/Pipfile index 473b873077..af3e02f54a 100644 --- a/Pipfile +++ b/Pipfile @@ -82,6 +82,7 @@ tqdm = "*" urllib3 = "*" utm = "*" websocket_client = "*" +hatanaka = "*" [requires] python_version = "3.8" diff --git a/Pipfile.lock b/Pipfile.lock index 4398c37d29..5ee3f2b031 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "918c8cba5c6a0242dc0f6ea74246176a1c54f0a9395feddf35af2189cc813378" + "sha256": "19a7b58f24cd7542ccb9fd386c7716d77fff3c1f87de496f3f42753cf34a5dde" }, "pipfile-spec": 6, "requires": { @@ -281,6 +281,16 @@ "index": "pypi", "version": "==20.1.0" }, + "hatanaka": { + "hashes": [ + "sha256:0e095d35ed4f607eb77ae47ecb310e4c25f5a6267037b703ea258ed03e5c47da", + "sha256:84faa953b4f641a6d3cf8187f1775ba7e7f8d815f7bcd48cfb18553b766cbc41", + "sha256:ccf8be554deee2fc70be52bd2f1d3d4dd370001caa74333bf041933d69a19023", + "sha256:ce1628029c6b50c142a8fc5f15453c4cf2a3fd88a7128075415aeb5c9a2727d0" + ], + "index": "pypi", + "version": "==2.8.0" + }, "hexdump": { "hashes": [ "sha256:d781a43b0c16ace3f9366aade73e8ad3a7bd5137d58f0b45ab2d3f54876f20db" @@ -304,12 +314,20 @@ "markers": "python_version < '3.10'", "version": "==4.11.3" }, + "importlib-resources": { + "hashes": [ + "sha256:b6062987dfc51f0fcb809187cffbd60f35df7acb4589091f154214af6d0d49d3", + "sha256:e447dc01619b1e951286f3929be820029d48c75eb25d265c28b92a16548212b8" + ], + "markers": "python_version >= '3.7'", + "version": "==5.7.1" + }, "isort": { "hashes": [ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", + "markers": "python_version < '4' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -449,6 +467,47 @@ ], "version": "==1.2.1" }, + "ncompress": { + "hashes": [ + "sha256:0349d7de11edd70a7efea9ce9dc67f0e47b5774832dd063f7ae68a9e3e36ea31", + "sha256:070044eab19586a45d1855c3e50e000ce86d6075b122a5ec8cffd480713dffac", + "sha256:13fa26ec8000d786a8079bb265508b5df4b445a4f460481a13549b4bd3c83824", + "sha256:15f10fbfa11345ff0af090e3e6ae13a1fe2b52a2bb39d4f2373c2d6aeac75e5d", + "sha256:2a104803fbe3ab0a96edb14927fa22c8142be838aabe7e938b4a52a4e82db56e", + "sha256:34754041d9bac2d6908ae0d07ba541e4d6d606cca222ddd53f3a57e15f386b0a", + "sha256:34c6496168fd4dbc13f1fc0c0fcbadded1957639956f8cbc6894c39999817e36", + "sha256:3590e66313041721ae81e72ece06b7048c9293321bb30900358638673608e264", + "sha256:393cc3c126b9451fb32fe2bc07773264c90e73afbd37da0df472ac23bfd1a2d5", + "sha256:5336a8831a7e587829ce54e9e27d1fb2e04ddbc7d2d983693e35a3a03ac3ce79", + "sha256:5a2ae8a9170fa1f45df7efa292eb8c437b18c225b63d4adca4f50f9da0e8e0c7", + "sha256:6540556d47670a8fb93878a44d0206bbdc87f32e4c5b57d6fe63691efafbb982", + "sha256:66d991155a1655ccd98e8433c4a7e811d63eb649adb55f47d8f9528a30cc4b7a", + "sha256:736dbae078107742cf6ac7ccc11ae9c5eab77ef2c02aab3ef64802877bb01cab", + "sha256:7608fbda43d04d9f476be2dbf4ef3c96e72d83b9557a48b07fbc9ff3ad29cdd2", + "sha256:78674f246878938387b6f82b10d1aa2192e02544d214541943d12ef1a45e66c6", + "sha256:8322482e72ac2802d1dca1007ec06aa281a4d5cf1cf9f8c75bb51e917382b756", + "sha256:8b9acc46cf36bb998ed215d6e76a94e2bd1e827b9a4cb5362982b7004b5a7620", + "sha256:8eb4a55cbeaeb238a3b412952077be6b3f37b3416cd0211cc22776391ff2fef7", + "sha256:916671d62167191af58d6b4a17b1c09c647e349dcff1fc0b7d764aa64c3773ee", + "sha256:94b3f4e851f5b37e1d4cf2d8da911fa10783a59cba3d7f1f2ae5bd2842558077", + "sha256:9cd040ad73a3b0e917e01cdfba507e10e0bb56849daaac3ac3d86382d4d7ad82", + "sha256:9d89acf209858e7940223cf35324e1b2effec119bb009a41f039e2ea4db22177", + "sha256:9da7c81313aed4b6c6e8020442ed8d03d04bff72947f9380ea1ce2c63ffb8ad1", + "sha256:aaa18a509d9fc173b4b47d53c834e43ced1eda63d2aa7d4613dc59b2f802a31a", + "sha256:ab9fc62baaa55faf8ed8ac67f2c64a7295fec91d7c1f306ac46aa894ca4edf91", + "sha256:af0011bae90e44121f4e4edbff3dccdce7e4c5fc5e354db7eb48410d71f496df", + "sha256:b031e06b42037b181e3514261e1e85a9eae4af990c12b9348a9f22b8042201ff", + "sha256:d11df815d280985dfa660974df11dbe051a1a18dca2f91f9d30fbd6548237b8f", + "sha256:d45ec59a8a3ce00613df0c81e5567854574dbbbf01ecd1a5a0929cd8fb04844d", + "sha256:da216a53db7cd4c0247376f87367dd71df457443567e55310f6d3d23a9aff2f2", + "sha256:e0ebd71990ef7909b6627b5341a2fe1977dcce61dd3760a29e19e3f9e4c6a275", + "sha256:e6f5bf381412e9d3847b76e8b6bd1f84dfadcd3d9c25903c8592facb437909a0", + "sha256:e7bbf10cca1376f4f17ae2c447e33a9d4067525abb0c71d488c9a5ced50552f1", + "sha256:f9ba6ab2aadd6fd90365fdad5219e4dc7bc2459b94f1e900a733dddaf4e9b2e6", + "sha256:fe0a671a2f7dc1ee0438d278ef30ab425a969536100c4352b5cb6bc0b6210818" + ], + "version": "==1.0.0" + }, "nose": { "hashes": [ "sha256:9ff7c6cc443f8c51994b34a667bbcf45afd6d945be7477b52e97516fd17c53ac", diff --git a/laika_repo b/laika_repo index 226adc655e..1fbc6780d5 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 226adc655e1488474468a97ab4a7705aad7e5837 +Subproject commit 1fbc6780d5184efd5ccf4518a01fe947ffbb4ba0 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py new file mode 100755 index 0000000000..28150bfea9 --- /dev/null +++ b/selfdrive/locationd/laikad.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 +from typing import List + +from cereal import log, messaging +from laika import AstroDog +from laika.helpers import UbloxGnssId +from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox + + +def correct_and_pos_fix(processed_measurements: List[GNSSMeasurement], dog: AstroDog): + # pos fix needs more than 5 processed_measurements + pos_fix = calc_pos_fix(processed_measurements) + + if len(pos_fix) == 0: + return [], [] + est_pos = pos_fix[0][:3] + corrected = correct_measurements(processed_measurements, est_pos, dog) + return calc_pos_fix(corrected), corrected + + +def process_ublox_msg(ublox_msg, dog, ublox_mono_time: int): + if ublox_msg.which == 'measurementReport': + report = ublox_msg.measurementReport + if len(report.measurements) == 0: + return None + new_meas = read_raw_ublox(report) + processed_measurements = process_measurements(new_meas, dog) + + corrected = correct_and_pos_fix(processed_measurements, dog) + pos_fix, _ = corrected + # todo send corrected messages instead of processed_measurements. Need fix for when having less than 6 measurements + correct_meas_msgs = [create_measurement_msg(m) for m in processed_measurements] + # pos fix can be an empty list if not enough correct measurements are available + if len(pos_fix) > 0: + corrected_pos = pos_fix[0][:3].tolist() + else: + corrected_pos = [0., 0., 0.] + dat = messaging.new_message('gnssMeasurements') + dat.gnssMeasurements = { + "position": corrected_pos, + "ubloxMonoTime": ublox_mono_time, + "correctedMeasurements": correct_meas_msgs + } + return dat + + +def create_measurement_msg(meas: GNSSMeasurement): + c = log.GnssMeasurements.CorrectedMeasurement.new_message() + ublox_gnss_id = meas.ublox_gnss_id + if ublox_gnss_id is None: + # todo never happens will fix in later pr + ublox_gnss_id = UbloxGnssId.GPS + c.constellationId = ublox_gnss_id.value + c.svId = int(meas.prn[1:]) + c.glonassFrequency = meas.glonass_freq if meas.ublox_gnss_id == UbloxGnssId.GLONASS else 0 + c.pseudorange = float(meas.observables['C1C']) # todo should be observables_final when using corrected measurements + c.pseudorangeStd = float(meas.observables_std['C1C']) + c.pseudorangeRate = float(meas.observables['D1C']) # todo should be observables_final when using corrected measurements + c.pseudorangeRateStd = float(meas.observables_std['D1C']) + c.satPos = meas.sat_pos_final.tolist() + c.satVel = meas.sat_vel.tolist() + return c + + +def main(): + dog = AstroDog() + sm = messaging.SubMaster(['ubloxGnss']) + pm = messaging.PubMaster(['gnssMeasurements']) + + while True: + sm.update() + + # Todo if no internet available use latest ephemeris + if sm.updated['ubloxGnss']: + ublox_msg = sm['ubloxGnss'] + msg = process_ublox_msg(ublox_msg, dog, sm.logMonoTime['ubloxGnss']) + if msg is None: + msg = messaging.new_message('gnssMeasurements') + pm.send('gnssMeasurements', msg) + + + +if __name__ == "__main__": + main() diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py new file mode 100755 index 0000000000..877623f0bd --- /dev/null +++ b/selfdrive/locationd/test/test_laikad.py @@ -0,0 +1,23 @@ +#!/usr/bin/env python3 +import unittest +from datetime import datetime + +from laika.helpers import UbloxGnssId + +from laika.gps_time import GPSTime +from laika.raw_gnss import GNSSMeasurement +from selfdrive.locationd.laikad import create_measurement_msg + + +class TestLaikad(unittest.TestCase): + + def test_create_msg_without_errors(self): + gpstime = GPSTime.from_datetime(datetime.now()) + meas = GNSSMeasurement('G01', gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}, ublox_gnss_id=UbloxGnssId.GPS) + msg = create_measurement_msg(meas) + + self.assertEqual(msg.constellationId, 'gps') + + +if __name__ == "__main__": + unittest.main() From 634f630e08c2ad91701a1f3c80574549fd12170c Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 06:44:09 -0700 Subject: [PATCH 047/391] Bump laika and cereal (#24451) --- cereal | 2 +- laika_repo | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 5935572cee..122dbf70d0 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 5935572cee86f202e2524d5f388f9475f92cd649 +Subproject commit 122dbf70d0fe71f9b7d3bf616b4e35b51c9fb04e diff --git a/laika_repo b/laika_repo index 1fbc6780d5..48a9cb686a 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 1fbc6780d5184efd5ccf4518a01fe947ffbb4ba0 +Subproject commit 48a9cb686ae2d12cd830f17c166a8fb9f79ab292 From e6f9f12d1c9faae8f718306bcd2862278a083351 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Fri, 6 May 2022 06:44:38 -0700 Subject: [PATCH 048/391] Test gnssUblox message processing (#24404) * Add simple test for processing ublox messages * Add simple test for processing ublox messages * Update selfdrive/locationd/test/test_ublox_processing.py Co-authored-by: Willem Melching * Update * Push laika ref Co-authored-by: Willem Melching --- .../locationd/test/test_ublox_processing.py | 80 +++++++++++++++++++ 1 file changed, 80 insertions(+) create mode 100755 selfdrive/locationd/test/test_ublox_processing.py diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py new file mode 100755 index 0000000000..94fddb9392 --- /dev/null +++ b/selfdrive/locationd/test/test_ublox_processing.py @@ -0,0 +1,80 @@ +import unittest + +import numpy as np + +from laika import AstroDog +from laika.helpers import UbloxGnssId +from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox +from selfdrive.test.openpilotci import get_url +from tools.lib.logreader import LogReader + + +def get_gnss_measurements(log_reader): + gnss_measurements = [] + for msg in log_reader: + if msg.which() == "ubloxGnss": + ublox_msg = msg.ubloxGnss + if ublox_msg.which == 'measurementReport': + report = ublox_msg.measurementReport + if len(report.measurements) > 0: + gnss_measurements.append(read_raw_ublox(report)) + return gnss_measurements + + +class TestUbloxProcessing(unittest.TestCase): + NUM_TEST_PROCESS_MEAS = 10 + + @classmethod + def setUpClass(cls): + lr = LogReader(get_url("4cf7a6ad03080c90|2021-09-29--13-46-36", 0)) + cls.gnss_measurements = get_gnss_measurements(lr) + + def test_read_ublox_raw(self): + count_gps = 0 + count_glonass = 0 + for measurements in self.gnss_measurements: + for m in measurements: + if m.ublox_gnss_id == UbloxGnssId.GPS: + count_gps += 1 + elif m.ublox_gnss_id == UbloxGnssId.GLONASS: + count_glonass += 1 + + self.assertEqual(count_gps, 5036) + self.assertEqual(count_glonass, 3651) + + def test_get_fix(self): + dog = AstroDog() + position_fix_found = 0 + count_processed_measurements = 0 + count_corrected_measurements = 0 + position_fix_found_after_correcting = 0 + + pos_ests = [] + for measurements in self.gnss_measurements[:self.NUM_TEST_PROCESS_MEAS]: + processed_meas = process_measurements(measurements, dog) + count_processed_measurements += len(processed_meas) + pos_fix = calc_pos_fix(processed_meas) + if len(pos_fix) > 0 and all(pos_fix[0] != 0): + position_fix_found += 1 + + corrected_meas = correct_measurements(processed_meas, pos_fix[0][:3], dog) + count_corrected_measurements += len(corrected_meas) + + pos_fix = calc_pos_fix(corrected_meas) + if len(pos_fix) > 0 and all(pos_fix[0] != 0): + pos_ests.append(pos_fix[0]) + position_fix_found_after_correcting += 1 + + mean_fix = np.mean(np.array(pos_ests)[:, :3], axis=0) + np.testing.assert_allclose(mean_fix, [-2452306.662377, -4778343.136806, 3428550.090557], rtol=0, atol=1) + + # Note that can happen that there are less corrected measurements compared to processed when they are invalid. + # However, not for the current segment + self.assertEqual(position_fix_found, self.NUM_TEST_PROCESS_MEAS) + self.assertEqual(position_fix_found_after_correcting, self.NUM_TEST_PROCESS_MEAS) + self.assertEqual(count_processed_measurements, 69) + self.assertEqual(count_corrected_measurements, 69) + + +if __name__ == "__main__": + unittest.main() From 85975e3dd91421ac3fffd03f75428257ce42b5b8 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 16:32:44 +0200 Subject: [PATCH 049/391] test_debayer.py some PC fixes (#24449) * test_debayer.py some PC fixes * fix rgb shape --- selfdrive/test/process_replay/.gitignore | 1 + selfdrive/test/process_replay/test_debayer.py | 24 +++++++++++++------ 2 files changed, 18 insertions(+), 7 deletions(-) diff --git a/selfdrive/test/process_replay/.gitignore b/selfdrive/test/process_replay/.gitignore index a35cd58d41..63c37e64e1 100644 --- a/selfdrive/test/process_replay/.gitignore +++ b/selfdrive/test/process_replay/.gitignore @@ -1 +1,2 @@ fakedata/ +debayer_diff.txt diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py index 17fa9afd63..6488184263 100755 --- a/selfdrive/test/process_replay/test_debayer.py +++ b/selfdrive/test/process_replay/test_debayer.py @@ -24,9 +24,11 @@ UV_WIDTH = FRAME_WIDTH // 2 UV_HEIGHT = FRAME_HEIGHT // 2 UV_SIZE = UV_WIDTH * UV_HEIGHT + def get_frame_fn(ref_commit, test_route, tici=True): return f"{test_route}_debayer{'_tici' if tici else ''}_{ref_commit}.bz2" + def bzip_frames(frames): data = bytes() for y, u, v in frames: @@ -35,6 +37,7 @@ def bzip_frames(frames): data += v.tobytes() return bz2.compress(data) + def unbzip_frames(url): with FileReader(url) as f: dat = f.read() @@ -54,14 +57,15 @@ def unbzip_frames(url): return res -def init_kernels(): - ctx = cl.create_some_context() + +def init_kernels(frame_offset=0): + ctx = cl.create_some_context(interactive=False) with open(os.path.join(BASEDIR, 'selfdrive/camerad/cameras/real_debayer.cl')) as f: build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ - f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DCAM_NUM=0' + f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DFRAME_OFFSET={frame_offset} -DCAM_NUM=0' if PC: - build_args += ' -DHALF_AS_FLOAT=1' + build_args += ' -DHALF_AS_FLOAT=1 -cl-std=CL2.0' debayer_prg = cl.Program(ctx, f.read()).build(options=build_args) with open(os.path.join(BASEDIR, 'selfdrive/camerad/transforms/rgb_to_yuv.cl')) as f: @@ -72,7 +76,8 @@ def init_kernels(): return ctx, debayer_prg, rgb_to_yuv_prg -def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): + +def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data, rgb=False): q = cl.CommandQueue(ctx) rgb_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT * 3, dtype=np.uint8) @@ -101,7 +106,11 @@ def debayer_frame(ctx, debayer_prg, rgb_to_yuv_prg, data): u = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT:FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE].reshape((UV_HEIGHT, UV_WIDTH)) v = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE:].reshape((UV_HEIGHT, UV_WIDTH)) - return y, u, v + if rgb: + return rgb_buff.reshape((FRAME_HEIGHT, FRAME_WIDTH, 3))[:, :, (2, 1, 0)] + else: + return y, u, v + def debayer_replay(lr): ctx, debayer_prg, rgb_to_yuv_prg = init_kernels() @@ -118,6 +127,7 @@ def debayer_replay(lr): return frames + if __name__ == "__main__": update = "--update" in sys.argv replay_dir = os.path.dirname(os.path.abspath(__file__)) @@ -179,7 +189,7 @@ if __name__ == "__main__": failed = True # upload new refs - if update or failed: + if update or (failed and TICI): from selfdrive.test.openpilotci import upload_file print("Uploading new refs") From 9ef17a877fa0cb4b0d9e7017c152dadbfb94a9aa Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Fri, 6 May 2022 17:27:54 +0200 Subject: [PATCH 050/391] sanity check on debayer time in CI (#24453) * check debayer time * set actual threshold * also print mean and max --- selfdrive/test/test_onroad.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 830522ec5e..21696645cd 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -181,6 +181,20 @@ class TestOnroad(unittest.TestCase): cpu_ok = check_cpu_usage(proclogs[0], proclogs[-1]) self.assertTrue(cpu_ok) + def test_camera_processing_time(self): + result = "\n" + result += "------------------------------------------------\n" + result += "-------------- Debayer Timing ------------------\n" + result += "------------------------------------------------\n" + + ts = [getattr(getattr(m, m.which()), "processingTime") for m in self.lr if 'CameraState' in m.which()] + self.assertLess(min(ts), 0.025, f"high execution time: {min(ts)}") + result += f"execution time: min {min(ts):.5f}s\n" + result += f"execution time: max {max(ts):.5f}s\n" + result += f"execution time: mean {np.mean(ts):.5f}s\n" + result += "------------------------------------------------\n" + print(result) + def test_mpc_execution_timings(self): result = "\n" result += "------------------------------------------------\n" From 49e10dc773780884f2aab309b7dc2436fe6f473a Mon Sep 17 00:00:00 2001 From: Joost Wooning Date: Fri, 6 May 2022 18:27:41 +0200 Subject: [PATCH 051/391] debayering: fill outer image borders (#24441) * debayering: fill outer image borders * correct conditions * try something else * remove global check * update ref Co-authored-by: Comma Device --- selfdrive/camerad/cameras/real_debayer.cl | 28 +++++++++---------- .../process_replay/debayer_replay_ref_commit | 2 +- 2 files changed, 14 insertions(+), 16 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 783abaabb4..6be53c2144 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -111,34 +111,32 @@ __kernel void debayer10(const __global uchar * in, int localColOffset = -1; int globalColOffset = -1; + const int x_global_mod = (x_global == 0 || x_global == RGB_WIDTH - 1) ? -1: 1; + const int y_global_mod = (y_global == 0 || y_global == RGB_HEIGHT - 1) ? -1: 1; + // cache padding - if (x_global >= 1 && x_local < 1) { + if (x_local < 1) { localColOffset = x_local; globalColOffset = -1; - cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-1, y_global, black_level); - } else if (x_global < RGB_WIDTH - 1 && x_local >= get_local_size(0) - 1) { + cached[(y_local + 1) * localRowLen + x_local] = val_from_10(in, x_global-x_global_mod, y_global, black_level); + } else if (x_local >= get_local_size(0) - 1) { localColOffset = x_local + 2; globalColOffset = 1; - cached[localOffset + 1] = val_from_10(in, x_global+1, y_global, black_level); + cached[localOffset + 1] = val_from_10(in, x_global+x_global_mod, y_global, black_level); } - if (y_global >= 1 && y_local < 1) { - cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-1, black_level); + if (y_local < 1) { + cached[y_local * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global-y_global_mod, black_level); if (localColOffset != -1) { - cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global-1, black_level); + cached[y_local * localRowLen + localColOffset] = val_from_10(in, x_global+(x_global_mod*globalColOffset), y_global-y_global_mod, black_level); } - } else if (y_global < RGB_HEIGHT - 1 && y_local >= get_local_size(1) - 1) { - cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+1, black_level); + } else if (y_local >= get_local_size(1) - 1) { + cached[(y_local + 2) * localRowLen + x_local + 1] = val_from_10(in, x_global, y_global+y_global_mod, black_level); if (localColOffset != -1) { - cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+globalColOffset, y_global+1, black_level); + cached[(y_local + 2) * localRowLen + localColOffset] = val_from_10(in, x_global+(x_global_mod*globalColOffset), y_global+y_global_mod, black_level); } } - // don't care - if (x_global < 1 || x_global >= RGB_WIDTH - 1 || y_global < 1 || y_global >= RGB_HEIGHT - 1) { - return; - } - // sync barrier(CLK_LOCAL_MEM_FENCE); diff --git a/selfdrive/test/process_replay/debayer_replay_ref_commit b/selfdrive/test/process_replay/debayer_replay_ref_commit index 44fe33001c..2f37c33669 100644 --- a/selfdrive/test/process_replay/debayer_replay_ref_commit +++ b/selfdrive/test/process_replay/debayer_replay_ref_commit @@ -1 +1 @@ -1f9907122a9bda9279d73f698addaa0e22796059 \ No newline at end of file +14f411de8085d1cc9e467592c90bcaf95447a467 \ No newline at end of file From 7bcecbfd0d1b3d5f47e263b86d64012f30944ab5 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 11:20:04 -0700 Subject: [PATCH 052/391] cell testing script --- scripts/cell.sh | 5 +++++ 1 file changed, 5 insertions(+) create mode 100755 scripts/cell.sh diff --git a/scripts/cell.sh b/scripts/cell.sh new file mode 100755 index 0000000000..cae701eccc --- /dev/null +++ b/scripts/cell.sh @@ -0,0 +1,5 @@ +#!/usr/bin/bash + +nmcli connection modify --temporary lte ipv4.route-metric 1 +nmcli connection modify --temporary lte ipv6.route-metric 1 +nmcli con up lte From 43912eb2523ea0b36183138cf1c800c63b01bcbb Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 13:21:08 -0700 Subject: [PATCH 053/391] update issue template --- .github/ISSUE_TEMPLATE/bug_report.yml | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml index 6bbbbacb70..b1a14076ea 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.yml +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -22,23 +22,11 @@ body: validations: required: true - - type: dropdown - id: hw - attributes: - label: What hardware does this issue affect? - multiple: true - options: - - comma three - - comma two - - EON Gold - validations: - required: true - - type: input id: route attributes: label: Provide a route where the issue occurs - description: Ensure the route is fully uploaded at https://useradmin.comma.ai + description: Ensure the route is fully uploaded at https://useradmin.comma.ai. We cannot look into issues without routes, or at least a Dongle ID. placeholder: 77611a1fac303767|2020-05-11--16-37-07 validations: required: true From f1bae8ca8832fd9a408a60863e735c642c9e6b6d Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Fri, 6 May 2022 13:21:38 -0700 Subject: [PATCH 054/391] remove from car bug too --- .github/ISSUE_TEMPLATE/car_bug_report.yml | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/car_bug_report.yml b/.github/ISSUE_TEMPLATE/car_bug_report.yml index a48f984192..23527c3a43 100644 --- a/.github/ISSUE_TEMPLATE/car_bug_report.yml +++ b/.github/ISSUE_TEMPLATE/car_bug_report.yml @@ -21,18 +21,6 @@ body: validations: required: true - - type: dropdown - id: hw - attributes: - label: What hardware does this issue affect? - multiple: true - options: - - comma three - - comma two - - EON Gold - validations: - required: true - - type: input id: car attributes: From ed3be29bfa975a4cbdb4abf85cda3726f64e3caf Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 6 May 2022 16:31:21 -0700 Subject: [PATCH 055/391] no encoder throttle (#24457) Co-authored-by: Comma Device --- selfdrive/hardware/tici/hardware.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index c626c5f825..1005866d69 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -468,6 +468,10 @@ class Tici(HardwareBase): sudo_write("performance", "/sys/class/devfreq/soc:qcom,memlat-cpu0/governor") sudo_write("performance", "/sys/class/devfreq/soc:qcom,memlat-cpu4/governor") + # *** VIDC (encoder) config *** + sudo_write("N", "/sys/kernel/debug/msm_vidc/clock_scaling") + sudo_write("Y", "/sys/kernel/debug/msm_vidc/disable_thermal_mitigation") + def configure_modem(self): sim_id = self.get_sim_info().get('sim_id', '') From c955e273d40dfd5c07a8505dbaf7b34766eee42f Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 6 May 2022 16:56:40 -0700 Subject: [PATCH 056/391] Toyota: fill steerFaultPermanent (#24410) * Toyota: fill steerFaultPermanent * same behavior as before, 0 is also fault (0 is most likely initializing) * think this was just wrong (2 or 10 would mean we think it's a fault) --- selfdrive/car/toyota/carcontroller.py | 3 +-- selfdrive/car/toyota/carstate.py | 7 ++++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 1c01703d7e..33e3fe118e 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -54,8 +54,7 @@ class CarController: apply_steer = apply_toyota_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.torque_rate_limits) self.steer_rate_limited = new_steer != apply_steer - # Cut steering while we're in a known fault state (2s) - if not CC.latActive or CS.steer_state in (9, 25): + if not CC.latActive: apply_steer = 0 apply_steer_req = 0 else: diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 54922ac2de..281d01026f 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -82,7 +82,10 @@ class CarState(CarStateBase): ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale # we could use the override bit from dbc, but it's triggered at too high torque values ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] not in (1, 5) + # steer rate fault, goes to 21 or 25 for 1 frame, then 9 for ~2 seconds + ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in (0, 9, 21, 25) + # 17 is a fault from a prolonged high torque delta between cmd and user + ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] == 17 if self.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 @@ -120,8 +123,6 @@ class CarState(CarStateBase): ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 - # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state - self.steer_state = cp.vl["EPS_STATUS"]["LKA_STATE"] if self.CP.enableBsm: ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) From ac343433a22984109401a9de97eab28220e38e72 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Fri, 6 May 2022 21:47:58 -0700 Subject: [PATCH 057/391] sync qcam p frames (#24459) Co-authored-by: Comma Device --- cereal | 2 +- selfdrive/loggerd/v4l_encoder.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cereal b/cereal index 122dbf70d0..c7d3a0acba 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit 122dbf70d0fe71f9b7d3bf616b4e35b51c9fb04e +Subproject commit c7d3a0acbae267ef93d30044e1941e060dac9e48 diff --git a/selfdrive/loggerd/v4l_encoder.cc b/selfdrive/loggerd/v4l_encoder.cc index b61bf01019..99653758a0 100644 --- a/selfdrive/loggerd/v4l_encoder.cc +++ b/selfdrive/loggerd/v4l_encoder.cc @@ -286,7 +286,7 @@ V4LEncoder::V4LEncoder( struct v4l2_control ctrls[] = { { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 15}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 14}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, From 29afd53d88f5c98efdac8727f3df1e4679790cde Mon Sep 17 00:00:00 2001 From: HaraldSchafer Date: Fri, 6 May 2022 22:17:21 -0700 Subject: [PATCH 058/391] Latcontrol torque: fix integrator induced ping pong (#24458) * Latcontrol torque: fix integrator induced ping pong * Reset on disengage since unwind resets anywayh * Might be overkill * rm whitespace * update ref --- selfdrive/car/toyota/tunes.py | 2 +- selfdrive/controls/lib/latcontrol_torque.py | 3 ++- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 50b03b85ad..7411c0c543 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -56,7 +56,7 @@ def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=.1): tune.torque.useSteeringAngle = True tune.torque.kp = 1.0 / MAX_LAT_ACCEL tune.torque.kf = 1.0 / MAX_LAT_ACCEL - tune.torque.ki = 0.25 / MAX_LAT_ACCEL + tune.torque.ki = 0.1 / MAX_LAT_ACCEL tune.torque.friction = FRICTION elif name == LatTunes.INDI_PRIUS: tune.init('indi') diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 4e9d559798..a373384254 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -42,7 +42,8 @@ class LatControlTorque(LatControl): if CS.vEgo < MIN_STEER_SPEED or not active: output_torque = 0.0 pid_log.active = False - self.pid.reset() + if not active: + self.pid.reset() else: if self.use_steering_angle: actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 5bed2e765c..ac8f59b26b 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -70d79fbcc2b9ab0af867a7d6f138b58bcaaa3aa8 \ No newline at end of file +10b766fa845934f0258c52cdf2103d0e1a9496c9 \ No newline at end of file From 75efad52eabf008ad87337b1e5fadadaaf21756c Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 01:00:43 -0700 Subject: [PATCH 059/391] Chrysler: add ACC fault signal (#24398) * add accFaulted event for Chrysler * add the signal * no class variables * available when not 1 * revert * bump opendbc to master * if not 0 --- opendbc | 2 +- selfdrive/car/chrysler/carstate.py | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/opendbc b/opendbc index e19ba095c3..919154efe2 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit e19ba095c3ee288d629284e24ec7e0deaf645f3f +Subproject commit 919154efe2bd07c4dd124d7e6a11a4afc8685f9d diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 5f83bbde8b..6dcd2cea62 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -53,6 +53,7 @@ class CarState(CarStateBase): ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) + ret.accFaulted = cp.vl["ACC_2"]["ACC_FAULTED"] != 0 ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -93,6 +94,7 @@ class CarState(CarStateBase): ("STEERING_RATE", "STEERING"), ("TURN_SIGNALS", "STEERING_LEVERS"), ("ACC_STATUS_2", "ACC_2"), + ("ACC_FAULTED", "ACC_2"), ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), ("CRUISE_STATE", "DASHBOARD"), From ed41b14b55426fe4400e1a87ac7c4e9d4f031b40 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 01:23:19 -0700 Subject: [PATCH 060/391] Chrysler: reduce ACC faults when disengaging on gas (#24445) --- selfdrive/car/chrysler/carcontroller.py | 3 +-- selfdrive/car/chrysler/carstate.py | 3 +++ selfdrive/car/chrysler/chryslercan.py | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index eda00a2ea1..3d6295d77d 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -49,8 +49,7 @@ class CarController: # *** control msgs *** if CC.cruiseControl.cancel: - # TODO: would be better to start from frame_2b3 - can_sends.append(create_wheel_buttons(self.packer, self.frame, cancel=True)) + can_sends.append(create_wheel_buttons(self.packer, CS.button_counter + 1, cancel=True)) # LKAS_HEARTBIT is forwarded by Panda so no need to send it here. # frame is 100Hz (0.01s period) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 6dcd2cea62..8ddf1c8684 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -70,6 +70,7 @@ class CarState(CarStateBase): self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"] self.lkas_car_model = cp_cam.vl["LKAS_HUD"]["CAR_MODEL"] self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"] + self.button_counter = cp.vl["WHEEL_BUTTONS"]["COUNTER"] return ret @@ -104,6 +105,7 @@ class CarState(CarStateBase): ("COUNTER", "EPS_STATUS",), ("TRACTION_OFF", "TRACTION_BUTTON"), ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS"), + ("COUNTER", "WHEEL_BUTTONS"), ] checks = [ @@ -116,6 +118,7 @@ class CarState(CarStateBase): ("ACC_2", 50), ("GEAR", 50), ("ACCEL_GAS_134", 50), + ("WHEEL_BUTTONS", 50), ("DASHBOARD", 15), ("STEERING_LEVERS", 10), ("SEATBELT_STATUS", 2), diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index 33f614d75e..896a6b15da 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -52,6 +52,6 @@ def create_wheel_buttons(packer, frame, cancel=False): # WHEEL_BUTTONS (571) Message sent to cancel ACC. values = { "ACC_CANCEL": cancel, - "COUNTER": frame % 10 # FIXME: this counter is wrong + "COUNTER": frame % 0x10 } return packer.make_can_msg("WHEEL_BUTTONS", 0, values) From ba89faa5f77c76023f49b85888e6d6eb7f2e1a11 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Sat, 7 May 2022 15:42:47 +0200 Subject: [PATCH 061/391] uploader: ensure requests.put gets file like object (#24462) --- selfdrive/loggerd/uploader.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 87988171fb..74d45f01c9 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import bz2 +import io import json import os import random @@ -153,10 +154,11 @@ class Uploader(): self.last_resp = FakeResponse() else: with open(fn, "rb") as f: - data = f.read() - if key.endswith('.bz2') and not fn.endswith('.bz2'): - data = bz2.compress(data) + data = bz2.compress(f.read()) + data = io.BytesIO(data) + else: + data = f self.last_resp = requests.put(url, data=data, headers=headers, timeout=10) except Exception as e: From 191fbd4f67e7f878b518effd14411779b9435339 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Sat, 7 May 2022 21:34:17 -0700 Subject: [PATCH 062/391] Camry TSS2: use torque controller (#24268) * use measurements from harald * update from table * average of hybrid and non-hybrid --- selfdrive/car/toyota/interface.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 433058b3c0..559307ef2d 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -87,7 +87,10 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 13.7 tire_stiffness_factor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid - set_lat_tune(ret.lateralTuning, LatTunes.PID_C) + if candidate in (CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): + set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=2.4, FRICTION=0.05) + else: + set_lat_tune(ret.lateralTuning, LatTunes.PID_C) elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True From ce0cc1f228edc85e8a9153784dfb5475b8376fb3 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Sun, 8 May 2022 19:18:03 -0700 Subject: [PATCH 063/391] tici modem restart script --- selfdrive/hardware/tici/restart_modem.sh | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100755 selfdrive/hardware/tici/restart_modem.sh diff --git a/selfdrive/hardware/tici/restart_modem.sh b/selfdrive/hardware/tici/restart_modem.sh new file mode 100755 index 0000000000..14cace6ad0 --- /dev/null +++ b/selfdrive/hardware/tici/restart_modem.sh @@ -0,0 +1,13 @@ +#!/usr/bin/bash + +nmcli connection modify --temporary lte gsm.auto-config yes +nmcli connection modify --temporary lte gsm.home-only yes +nmcli connection modify --temporary lte connection.autoconnect-retries 20 + +# restart modem +sudo systemctl stop ModemManager +/usr/comma/lte/lte.sh stop_blocking +sudo systemctl restart lte + +#sudo systemctl restart ModemManager +sudo ModemManager --debug From f7c2eefad9897830bf7bce290dec1dfc7d97e1d2 Mon Sep 17 00:00:00 2001 From: Gijs Koning Date: Mon, 9 May 2022 04:05:08 -0700 Subject: [PATCH 064/391] Bump laika (#24454) * Fix after laika repo changes * Update laika --- laika_repo | 2 +- selfdrive/locationd/laikad.py | 10 +++------- selfdrive/locationd/test/test_laikad.py | 4 ++-- selfdrive/locationd/test/test_ublox_processing.py | 6 +++--- 4 files changed, 9 insertions(+), 13 deletions(-) diff --git a/laika_repo b/laika_repo index 48a9cb686a..be1a213a5f 160000 --- a/laika_repo +++ b/laika_repo @@ -1 +1 @@ -Subproject commit 48a9cb686ae2d12cd830f17c166a8fb9f79ab292 +Subproject commit be1a213a5ffa3cafe2b4f2d53f6df5d2452ad910 diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index 28150bfea9..4695fd945b 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -3,7 +3,7 @@ from typing import List from cereal import log, messaging from laika import AstroDog -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.raw_gnss import GNSSMeasurement, calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox @@ -46,13 +46,9 @@ def process_ublox_msg(ublox_msg, dog, ublox_mono_time: int): def create_measurement_msg(meas: GNSSMeasurement): c = log.GnssMeasurements.CorrectedMeasurement.new_message() - ublox_gnss_id = meas.ublox_gnss_id - if ublox_gnss_id is None: - # todo never happens will fix in later pr - ublox_gnss_id = UbloxGnssId.GPS - c.constellationId = ublox_gnss_id.value + c.constellationId = meas.constellation_id.value c.svId = int(meas.prn[1:]) - c.glonassFrequency = meas.glonass_freq if meas.ublox_gnss_id == UbloxGnssId.GLONASS else 0 + c.glonassFrequency = meas.glonass_freq if meas.constellation_id == ConstellationId.GLONASS else 0 c.pseudorange = float(meas.observables['C1C']) # todo should be observables_final when using corrected measurements c.pseudorangeStd = float(meas.observables_std['C1C']) c.pseudorangeRate = float(meas.observables['D1C']) # todo should be observables_final when using corrected measurements diff --git a/selfdrive/locationd/test/test_laikad.py b/selfdrive/locationd/test/test_laikad.py index 877623f0bd..fdbb46f5aa 100755 --- a/selfdrive/locationd/test/test_laikad.py +++ b/selfdrive/locationd/test/test_laikad.py @@ -2,7 +2,7 @@ import unittest from datetime import datetime -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.gps_time import GPSTime from laika.raw_gnss import GNSSMeasurement @@ -13,7 +13,7 @@ class TestLaikad(unittest.TestCase): def test_create_msg_without_errors(self): gpstime = GPSTime.from_datetime(datetime.now()) - meas = GNSSMeasurement('G01', gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}, ublox_gnss_id=UbloxGnssId.GPS) + meas = GNSSMeasurement(ConstellationId.GPS, 1, gpstime.week, gpstime.tow, {'C1C': 0., 'D1C': 0.}, {'C1C': 0., 'D1C': 0.}) msg = create_measurement_msg(meas) self.assertEqual(msg.constellationId, 'gps') diff --git a/selfdrive/locationd/test/test_ublox_processing.py b/selfdrive/locationd/test/test_ublox_processing.py index 94fddb9392..427003b24c 100755 --- a/selfdrive/locationd/test/test_ublox_processing.py +++ b/selfdrive/locationd/test/test_ublox_processing.py @@ -3,7 +3,7 @@ import unittest import numpy as np from laika import AstroDog -from laika.helpers import UbloxGnssId +from laika.helpers import ConstellationId from laika.raw_gnss import calc_pos_fix, correct_measurements, process_measurements, read_raw_ublox from selfdrive.test.openpilotci import get_url from tools.lib.logreader import LogReader @@ -34,9 +34,9 @@ class TestUbloxProcessing(unittest.TestCase): count_glonass = 0 for measurements in self.gnss_measurements: for m in measurements: - if m.ublox_gnss_id == UbloxGnssId.GPS: + if m.constellation_id == ConstellationId.GPS: count_gps += 1 - elif m.ublox_gnss_id == UbloxGnssId.GLONASS: + elif m.constellation_id == ConstellationId.GLONASS: count_glonass += 1 self.assertEqual(count_gps, 5036) From bf269bd883e77bf29e4d9a0a21ef0c4a9eb79c2c Mon Sep 17 00:00:00 2001 From: ntegan1 Date: Mon, 9 May 2022 15:07:19 -0400 Subject: [PATCH 065/391] Tools: allow uncompressed logs (#24471) --- tools/lib/route.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/lib/route.py b/tools/lib/route.py index 8092096a0b..067fccf188 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -8,9 +8,9 @@ from tools.lib.auth_config import get_token from tools.lib.api import CommaApi from tools.lib.helpers import RE -QLOG_FILENAMES = ['qlog.bz2'] +QLOG_FILENAMES = ['qlog', 'qlog.bz2'] QCAMERA_FILENAMES = ['qcamera.ts'] -LOG_FILENAMES = ['rlog.bz2', 'raw_log.bz2'] +LOG_FILENAMES = ['rlog', 'rlog.bz2', 'raw_log.bz2'] CAMERA_FILENAMES = ['fcamera.hevc', 'video.hevc'] DCAMERA_FILENAMES = ['dcamera.hevc'] ECAMERA_FILENAMES = ['ecamera.hevc'] From 6163dd5ca06efe05a7d4645f6b4127847ce133ac Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 May 2022 13:31:55 -0700 Subject: [PATCH 066/391] URLFile: raise exception if remote URL doesn't exist when using cache (#24432) * URLFile returns empty bytes if using cache and remote file doesn't exist * better exception * assert on cached files --- tools/lib/url_file.py | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 8ad2f96b3a..1e94a588f1 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -87,6 +87,7 @@ class URLFile: file_begin = self._pos file_end = self._pos + ll if ll is not None else self.get_length() + assert file_end != -1, f"Remote file is empty or doesn't exist: {self._url}" # We have to align with chunks we store. Position is the begginiing of the latest chunk that starts before or at our file position = (file_begin // CHUNK_SIZE) * CHUNK_SIZE response = b"" From 4354f7cd28168466faf5b338c1e86f8845c23e63 Mon Sep 17 00:00:00 2001 From: ZwX1616 Date: Mon, 9 May 2022 13:38:39 -0700 Subject: [PATCH 067/391] clean up gamma variable names (#24476) --- selfdrive/camerad/cameras/real_debayer.cl | 29 +++++++++++------------ 1 file changed, 14 insertions(+), 15 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index 6be53c2144..dee7f241a4 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -11,17 +11,17 @@ const __constant half3 color_correction_1 = (half3)(-0.5743977, 1.36858544, -0.5 const __constant half3 color_correction_2 = (half3)(-0.25277411, -0.05627105, 1.45875782); // tone mapping params -const half cpk = 0.75; -const half cpb = 0.125; -const half cpxk = 0.0025; -const half cpxb = 0.01; - -half mf(half x, half cp) { - half rk = 9 - 100*cp; - if (x > cp) { - return (rk * (x-cp) * (1-(cpk*cp+cpb)) * (1+1/(rk*(1-cp))) / (1+rk*(x-cp))) + cpk*cp + cpb; - } else if (x < cp) { - return (rk * (x-cp) * (cpk*cp+cpb) * (1+1/(rk*cp)) / (1-rk*(x-cp))) + cpk*cp + cpb; +const half gamma_k = 0.75; +const half gamma_b = 0.125; +const half mp_default = 0.01; // ideally midpoint should be adaptive + +half gamma_apply(half x, half mp) { + // poly approximation for s curve + half rk = 9 - 100*mp; + if (x > mp) { + return (rk * (x-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(x-mp))) + gamma_k*mp + gamma_b; + } else if (x < mp) { + return (rk * (x-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(x-mp))) + gamma_k*mp + gamma_b; } else { return x; } @@ -29,13 +29,12 @@ half mf(half x, half cp) { half3 color_correct(half3 rgb) { half3 ret = (half3)(0.0, 0.0, 0.0); - half cpx = 0.01; ret += (half)rgb.x * color_correction_0; ret += (half)rgb.y * color_correction_1; ret += (half)rgb.z * color_correction_2; - ret.x = mf(ret.x, cpx); - ret.y = mf(ret.y, cpx); - ret.z = mf(ret.z, cpx); + ret.x = gamma_apply(ret.x, mp_default); + ret.y = gamma_apply(ret.y, mp_default); + ret.z = gamma_apply(ret.z, mp_default); ret = clamp(0.0, 255.0, ret*255.0); return ret; } From dded24662f9f5ca0634033f63fa4ed9fa842bd97 Mon Sep 17 00:00:00 2001 From: George Hotz Date: Mon, 9 May 2022 13:33:33 -0700 Subject: [PATCH 068/391] update compressed vipc to function on packets --- tools/camerastream/compressed_vipc.py | 131 +++++++++++--------------- 1 file changed, 56 insertions(+), 75 deletions(-) diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index 67bc1ffb7b..c39ac955e6 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -1,120 +1,101 @@ #!/usr/bin/env python3 import os import sys +import argparse import numpy as np import multiprocessing +import time +import cereal.messaging as messaging from cereal.visionipc.visionipc_pyx import VisionIpcServer, VisionStreamType # pylint: disable=no-name-in-module, import-error -W, H = 1928, 1208 +W, H = 1928, 1208 V4L2_BUF_FLAG_KEYFRAME = 8 -def writer(fn, addr, sock_name): - import cereal.messaging as messaging - fifo_file = open(fn, "wb") +def decoder(addr, sock_name, vipc_server, vst, nvidia): + print("start decoder for %s" % sock_name) + if nvidia: + sys.path += os.environ["LD_LIBRARY_PATH"].split(":") + import PyNvCodec as nvc # pylint: disable=import-error + + nvDec = nvc.PyNvDecoder(W, H, nvc.PixelFormat.NV12, nvc.CudaVideoCodec.HEVC, 0) + cc1 = nvc.ColorspaceConversionContext(nvc.ColorSpace.BT_709, nvc.ColorRange.JPEG) + conv_yuv = nvc.PySurfaceConverter(W, H, nvc.PixelFormat.NV12, nvc.PixelFormat.YUV420, 0) + nvDwn_yuv = nvc.PySurfaceDownloader(W, H, nvc.PixelFormat.YUV420, 0) + img_yuv = np.ndarray((H*W//2*3), dtype=np.uint8) + else: + import av # pylint: disable=import-error + codec = av.CodecContext.create("hevc", "r") os.environ["ZMQ"] = "1" messaging.context = messaging.Context() - sock = messaging.sub_sock(sock_name, None, addr=addr, conflate=False) + cnt = 0 last_idx = -1 seen_iframe = False + + time_q = [] while 1: msgs = messaging.drain_sock(sock, wait_for_one=True) for evt in msgs: evta = getattr(evt, evt.which()) - lat = ((evt.logMonoTime/1e9) - (evta.idx.timestampEof/1e9))*1000 - print("%2d %4d %.3f %.3f latency %.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, lat), len(evta.data), sock_name) if evta.idx.encodeId != 0 and evta.idx.encodeId != (last_idx+1): - print("DROP!") + print("DROP PACKET!") last_idx = evta.idx.encodeId - if evta.idx.flags & V4L2_BUF_FLAG_KEYFRAME: - fifo_file.write(evta.header) - seen_iframe = True - if not seen_iframe: + if not seen_iframe and not (evta.idx.flags & V4L2_BUF_FLAG_KEYFRAME): print("waiting for iframe") continue - fifo_file.write(evta.data) + time_q.append(time.monotonic()) + latency = ((evt.logMonoTime/1e9) - (evta.idx.timestampEof/1e9))*1000 -FFMPEG_OPTIONS = {"probesize": "32", "flags": "low_delay"} + # put in header (first) + if not seen_iframe: + if nvidia: + nvDec.DecodeSurfaceFromPacket(np.frombuffer(evta.header, dtype=np.uint8)) + else: + codec.decode(av.packet.Packet(evta.header)) + seen_iframe = True -def decoder_nvidia(fn, vipc_server, vst, yuv=True, rgb=False): - sys.path.append("/raid.dell2/PyNvCodec") - import PyNvCodec as nvc # pylint: disable=import-error - decoder = nvc.PyNvDecoder(fn, 0, FFMPEG_OPTIONS) - cc1 = nvc.ColorspaceConversionContext(nvc.ColorSpace.BT_709, nvc.ColorRange.JPEG) + if nvidia: + rawSurface = nvDec.DecodeSurfaceFromPacket(np.frombuffer(evta.data, dtype=np.uint8)) + if rawSurface.Empty(): + print("DROP SURFACE") + continue + convSurface = conv_yuv.Execute(rawSurface, cc1) + nvDwn_yuv.DownloadSingleSurface(convSurface, img_yuv) + else: + frames = codec.decode(av.packet.Packet(evta.data)) + if len(frames) == 0: + print("DROP SURFACE") + continue + assert len(frames) == 1 + img_yuv = frames[0].to_ndarray(format=av.video.format.VideoFormat('yuv420p')) - if rgb: - conv = nvc.PySurfaceConverter(W, H, nvc.PixelFormat.NV12, nvc.PixelFormat.BGR, 0) - nvDwn = nvc.PySurfaceDownloader(W, H, nvc.PixelFormat.BGR, 0) - img = np.ndarray((H,W,3), dtype=np.uint8) + vipc_server.send(vst, img_yuv.flatten().data, cnt, 0, 0) + cnt += 1 - if yuv: - conv_yuv = nvc.PySurfaceConverter(W, H, nvc.PixelFormat.NV12, nvc.PixelFormat.YUV420, 0) - nvDwn_yuv = nvc.PySurfaceDownloader(W, H, nvc.PixelFormat.YUV420, 0) - img_yuv = np.ndarray((H*W//2*3), dtype=np.uint8) + pc_latency = (time.monotonic()-time_q[0])*1000 + time_q = time_q[1:] + print("%2d %4d %.3f %.3f latency %6.2fms + %6.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, latency, pc_latency), len(evta.data), sock_name) - cnt = 0 - while 1: - rawSurface = decoder.DecodeSingleSurface() - if rawSurface.Empty(): - continue - if rgb: - convSurface = conv.Execute(rawSurface, cc1) - nvDwn.DownloadSingleSurface(convSurface, img) - vipc_server.send(vst, img.flatten().data, cnt, 0, 0) - if yuv: - convSurface = conv_yuv.Execute(rawSurface, cc1) - nvDwn_yuv.DownloadSingleSurface(convSurface, img_yuv) - vipc_server.send(vst+3, img_yuv.flatten().data, cnt, 0, 0) - cnt += 1 - -def decoder_ffmpeg(fn, vipc_server, vst, yuv=True, rgb=False): - import av # pylint: disable=import-error - container = av.open(fn, options=FFMPEG_OPTIONS) - cnt = 0 - for frame in container.decode(video=0): - if rgb: - img = frame.to_ndarray(format=av.video.format.VideoFormat('bgr24')) - vipc_server.send(vst, img.flatten().data, cnt, 0, 0) - if yuv: - img_yuv = frame.to_ndarray(format=av.video.format.VideoFormat('yuv420p')) - vipc_server.send(vst+3, img_yuv.flatten().data, cnt, 0, 0) - cnt += 1 - -import argparse if __name__ == "__main__": parser = argparse.ArgumentParser(description='Decode video streams and broacast on VisionIPC') parser.add_argument("addr", help="Address of comma 3") - parser.add_argument('--pipes', action='store_true', help='Only create pipes') parser.add_argument('--nvidia', action='store_true', help='Use nvidia instead of ffmpeg') - parser.add_argument('--rgb', action='store_true', help='Also broadcast RGB') parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") args = parser.parse_args() all_cams = [ - ("roadEncodeData", VisionStreamType.VISION_STREAM_RGB_ROAD), - ("wideRoadEncodeData", VisionStreamType.VISION_STREAM_RGB_WIDE_ROAD), - ("driverEncodeData", VisionStreamType.VISION_STREAM_RGB_DRIVER), + ("roadEncodeData", VisionStreamType.VISION_STREAM_ROAD), + ("wideRoadEncodeData", VisionStreamType.VISION_STREAM_WIDE_ROAD), + ("driverEncodeData", VisionStreamType.VISION_STREAM_DRIVER), ] cams = dict([all_cams[int(x)] for x in args.cams.split(",")]) vipc_server = VisionIpcServer("camerad") for vst in cams.values(): - if args.rgb: - vipc_server.create_buffers(vst, 4, True, W, H) - vipc_server.create_buffers(vst+3, 4, False, W, H) + vipc_server.create_buffers(vst, 4, False, W, H) vipc_server.start_listener() for k,v in cams.items(): - FIFO_NAME = "/tmp/decodepipe_"+k - if os.path.exists(FIFO_NAME): - os.unlink(FIFO_NAME) - os.mkfifo(FIFO_NAME) - multiprocessing.Process(target=writer, args=(FIFO_NAME, sys.argv[1], k)).start() - if args.pipes: - print("connect to", FIFO_NAME) - elif args.nvidia: - multiprocessing.Process(target=decoder_nvidia, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start() - else: - multiprocessing.Process(target=decoder_ffmpeg, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start() + multiprocessing.Process(target=decoder, args=(args.addr, k, vipc_server, v, args.nvidia)).start() From 5ac22d80de5c37e059768ad210bee91cc73e025c Mon Sep 17 00:00:00 2001 From: Comma Device Date: Mon, 9 May 2022 14:06:39 -0700 Subject: [PATCH 069/391] faster modem restart --- selfdrive/hardware/tici/restart_modem.sh | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/selfdrive/hardware/tici/restart_modem.sh b/selfdrive/hardware/tici/restart_modem.sh index 14cace6ad0..2fa5e60619 100755 --- a/selfdrive/hardware/tici/restart_modem.sh +++ b/selfdrive/hardware/tici/restart_modem.sh @@ -1,13 +1,18 @@ #!/usr/bin/bash -nmcli connection modify --temporary lte gsm.auto-config yes nmcli connection modify --temporary lte gsm.home-only yes +nmcli connection modify --temporary lte gsm.auto-config yes nmcli connection modify --temporary lte connection.autoconnect-retries 20 -# restart modem sudo systemctl stop ModemManager -/usr/comma/lte/lte.sh stop_blocking -sudo systemctl restart lte + +# full restart +#/usr/comma/lte/lte.sh stop_blocking +#sudo systemctl restart lte + +# quick shutdown +/usr/comma/lte/lte.sh stop +nmcli con down lte #sudo systemctl restart ModemManager sudo ModemManager --debug From 32e4dc3869bd83f1a978d4a6dfab0238285f31a6 Mon Sep 17 00:00:00 2001 From: Ross Fisher Date: Mon, 9 May 2022 17:24:09 -0400 Subject: [PATCH 070/391] tools: add link to jungle repo (#24477) --- tools/replay/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/replay/README.md b/tools/replay/README.md index a0706d8df2..759a448d73 100644 --- a/tools/replay/README.md +++ b/tools/replay/README.md @@ -61,7 +61,7 @@ cd selfdrive/ui && ./watch3 ## Stream CAN messages to your device -Replay CAN messages as they were recorded using a [panda jungle](https://comma.ai/shop/products/panda-jungle). The jungle has 6x OBD-C ports for connecting all your comma devices. +Replay CAN messages as they were recorded using a [panda jungle](https://comma.ai/shop/products/panda-jungle). The jungle has 6x OBD-C ports for connecting all your comma devices. Check out the [jungle repo](https://github.com/commaai/panda_jungle) for more info. `can_replay.py` is a convenient script for when any CAN data will do. From b8dad70f702d31ad95f76649faa5edaeb759917e Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Mon, 9 May 2022 15:44:02 -0700 Subject: [PATCH 071/391] update python packages (#24478) --- Pipfile.lock | 774 +++++++++++++++++++++++++++++---------------------- 1 file changed, 434 insertions(+), 340 deletions(-) diff --git a/Pipfile.lock b/Pipfile.lock index 5ee3f2b031..d7372d3ca3 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -18,11 +18,11 @@ "default": { "astroid": { "hashes": [ - "sha256:8d0a30fe6481ce919f56690076eafbb2fb649142a89dc874f1ec0e7a011492d0", - "sha256:cc8cc0d2d916c42d0a7c476c57550a4557a083081976bf42a73414322a6411d9" + "sha256:14ffbb4f6aa2cf474a0834014005487f7ecd8924996083ab411e7fa0b508ce0b", + "sha256:f4e4ec5294c4b07ac38bab9ca5ddd3914d4bf46f9006eb5c0ae755755061044e" ], "markers": "python_full_version >= '3.6.2'", - "version": "==2.11.2" + "version": "==2.11.5" }, "atomicwrites": { "hashes": [ @@ -150,11 +150,11 @@ }, "click": { "hashes": [ - "sha256:24e1a4a9ec5bf6299411369b208c1df2188d9eb8d916302fe6bf03faed227f1e", - "sha256:479707fe14d9ec9a0757618b7a100a0ae4c4e236fac5b7f80ca68028141a1a72" + "sha256:7682dc8afb30297001674575ea00d1814d808d6a36af415a82bd481d37ba7b8e", + "sha256:bb4d8133cb15a609f44e8213d9b391b0809795062913b383c62be0ee95b1db48" ], "markers": "python_version >= '3.7'", - "version": "==8.1.2" + "version": "==8.1.3" }, "crcmod": { "hashes": [ @@ -168,29 +168,31 @@ }, "cryptography": { "hashes": [ - "sha256:0a3bf09bb0b7a2c93ce7b98cb107e9170a90c51a0162a20af1c61c765b90e60b", - "sha256:1f64a62b3b75e4005df19d3b5235abd43fa6358d5516cfc43d87aeba8d08dd51", - "sha256:32db5cc49c73f39aac27574522cecd0a4bb7384e71198bc65a0d23f901e89bb7", - "sha256:4881d09298cd0b669bb15b9cfe6166f16fc1277b4ed0d04a22f3d6430cb30f1d", - "sha256:4e2dddd38a5ba733be6a025a1475a9f45e4e41139d1321f412c6b360b19070b6", - "sha256:53e0285b49fd0ab6e604f4c5d9c5ddd98de77018542e88366923f152dbeb3c29", - "sha256:70f8f4f7bb2ac9f340655cbac89d68c527af5bb4387522a8413e841e3e6628c9", - "sha256:7b2d54e787a884ffc6e187262823b6feb06c338084bbe80d45166a1cb1c6c5bf", - "sha256:7be666cc4599b415f320839e36367b273db8501127b38316f3b9f22f17a0b815", - "sha256:8241cac0aae90b82d6b5c443b853723bcc66963970c67e56e71a2609dc4b5eaf", - "sha256:82740818f2f240a5da8dfb8943b360e4f24022b093207160c77cadade47d7c85", - "sha256:8897b7b7ec077c819187a123174b645eb680c13df68354ed99f9b40a50898f77", - "sha256:c2c5250ff0d36fd58550252f54915776940e4e866f38f3a7866d92b32a654b86", - "sha256:ca9f686517ec2c4a4ce930207f75c00bf03d94e5063cbc00a1dc42531511b7eb", - "sha256:d2b3d199647468d410994dbeb8cec5816fb74feb9368aedf300af709ef507e3e", - "sha256:da73d095f8590ad437cd5e9faf6628a218aa7c387e1fdf67b888b47ba56a17f0", - "sha256:e167b6b710c7f7bc54e67ef593f8731e1f45aa35f8a8a7b72d6e42ec76afd4b3", - "sha256:ea634401ca02367c1567f012317502ef3437522e2fc44a3ea1844de028fa4b84", - "sha256:ec6597aa85ce03f3e507566b8bcdf9da2227ec86c4266bd5e6ab4d9e0cc8dab2", - "sha256:f64b232348ee82f13aac22856515ce0195837f6968aeaa94a3d0353ea2ec06a6" - ], - "index": "pypi", - "version": "==36.0.2" + "sha256:093cb351031656d3ee2f4fa1be579a8c69c754cf874206be1d4cf3b542042804", + "sha256:0cc20f655157d4cfc7bada909dc5cc228211b075ba8407c46467f63597c78178", + "sha256:1b9362d34363f2c71b7853f6251219298124aa4cc2075ae2932e64c91a3e2717", + "sha256:1f3bfbd611db5cb58ca82f3deb35e83af34bb8cf06043fa61500157d50a70982", + "sha256:2bd1096476aaac820426239ab534b636c77d71af66c547b9ddcd76eb9c79e004", + "sha256:31fe38d14d2e5f787e0aecef831457da6cec68e0bb09a35835b0b44ae8b988fe", + "sha256:3b8398b3d0efc420e777c40c16764d6870bcef2eb383df9c6dbb9ffe12c64452", + "sha256:3c81599befb4d4f3d7648ed3217e00d21a9341a9a688ecdd615ff72ffbed7336", + "sha256:419c57d7b63f5ec38b1199a9521d77d7d1754eb97827bbb773162073ccd8c8d4", + "sha256:46f4c544f6557a2fefa7ac8ac7d1b17bf9b647bd20b16decc8fbcab7117fbc15", + "sha256:471e0d70201c069f74c837983189949aa0d24bb2d751b57e26e3761f2f782b8d", + "sha256:59b281eab51e1b6b6afa525af2bd93c16d49358404f814fe2c2410058623928c", + "sha256:731c8abd27693323b348518ed0e0705713a36d79fdbd969ad968fbef0979a7e0", + "sha256:95e590dd70642eb2079d280420a888190aa040ad20f19ec8c6e097e38aa29e06", + "sha256:a68254dd88021f24a68b613d8c51d5c5e74d735878b9e32cc0adf19d1f10aaf9", + "sha256:a7d5137e556cc0ea418dca6186deabe9129cee318618eb1ffecbd35bee55ddc1", + "sha256:aeaba7b5e756ea52c8861c133c596afe93dd716cbcacae23b80bc238202dc023", + "sha256:dc26bb134452081859aa21d4990474ddb7e863aa39e60d1592800a8865a702de", + "sha256:e53258e69874a306fcecb88b7534d61820db8a98655662a3dd2ec7f1afd9132f", + "sha256:ef15c2df7656763b4ff20a9bc4381d8352e6640cfeb95c2972c38ef508e75181", + "sha256:f224ad253cc9cea7568f49077007d2263efa57396a2f2f78114066fd54b5c68e", + "sha256:f8ec91983e638a9bcd75b39f1396e5c0dc2330cbd9ce4accefe68717e6779e0a" + ], + "index": "pypi", + "version": "==37.0.2" }, "cython": { "hashes": [ @@ -252,11 +254,11 @@ }, "flask": { "hashes": [ - "sha256:8a4cf32d904cf5621db9f0c9fbcd7efabf3003f22a04e4d0ce790c7137ec5264", - "sha256:a8c9bd3e558ec99646d177a9739c41df1ded0629480b4c8d2975412f3c9519c8" + "sha256:315ded2ddf8a6281567edb27393010fe3406188bafbfe65a3339d5787d89e477", + "sha256:fad5b446feb0d6db6aec0c3184d16a8c1f6c3e464b511649c8918a9be100b4fe" ], "index": "pypi", - "version": "==2.1.1" + "version": "==2.1.2" }, "flatbuffers": { "hashes": [ @@ -281,6 +283,43 @@ "index": "pypi", "version": "==20.1.0" }, + "h3": { + "hashes": [ + "sha256:08a09f7a43ed142573c602ef487a058da54ab4d86c173082b29a5057805fe2d3", + "sha256:0a96ea1844182bd0511cdcdc89e38e3026d9a3d4139fd0c5e899709edd798ffa", + "sha256:1387166f453816f91d624c6ce70876a3c20356cd28a3a759920dee23c78684cf", + "sha256:25f0c22f4802ab71c45b86d206bd30fa0a6c7fbc3b630398b60c22907e9742e6", + "sha256:2bf4d75fe42a260ac23bf4cb9f9de6e6f2aa37279b2719387711f3e0727c4653", + "sha256:2faf304020493c5ffede34264bd28ed529b8b7238103e0904c0f3e9ca880bcfd", + "sha256:33b147ecc0e19ab1f27303d0e3ae28e5a457f3347ce18ca9a58b694a8b0cdd0a", + "sha256:38a084d74b234d48aafc01e4329cd9a92966e3f45b8cf21224118643b6eaa1c0", + "sha256:3b1642085939c597a9c723ae3b187f80527ffc79cad0ded0e55be9c9bac69c6c", + "sha256:4469fdf90034b1a67e155cac4f46b077fdc404b6182ab33abcb7081c9bfbf411", + "sha256:46a1284521d86cab414981056390be944dca780fe74c6c9e463a16d1c8d24871", + "sha256:585f375ba2a95ceb16b115a378e9118159c912c26703cf1627f57a004818c3b3", + "sha256:62057c1c3d1c7fe492841e42fa360825d66fafd55ac37dc4e90b2292af21cb47", + "sha256:68227df989274b0da54de9101a50741c70c48197ba3beacfb97c88170445c18e", + "sha256:7b0ddfdd02920996d7c6672c91e83efb5432c67ff83f89a03f774e84bcfe19f8", + "sha256:7c5366d24c2c01ef3bae68547c15f1965fac6053b2596c0073766bf7544ecaf0", + "sha256:8155b2de1938eb56128fe4fd96e4f6d2022d4c34d8137bc95d73cbf329f8f89e", + "sha256:83c2b0cd8259541f95b0493a620fb781b6a18c7c1e8fac1bda4fb234ae23ab43", + "sha256:8d03622433da1a2761574311af378ff1ff841f5956db25927837c6aee9d1c13c", + "sha256:960cd005b8817314d95fbaff3e848a72385df4e3c6c9703ff99b08581c8def69", + "sha256:9b0277d82578b3ed3220167ef5c5acd8b4e0ef2fcd6c2fd69dbf29e0c4e03765", + "sha256:a33fae02a54c63acb3c30fe49388715d658d76d42858a6ad4563e7e6859a9e57", + "sha256:a59d7d10597a2da9e9729637a625ae8dff2ed4e7c6c0b4952f0a5b2db6ef7152", + "sha256:ad21cfa8d97a62984ce30692a7ddf71a32a0c744cc247c43cbdbac1536aec4de", + "sha256:be63482de86bbb91db7f3f3b7dd452b9e08a11dacbda2088386831fb0e7de59c", + "sha256:c1108a9acb755310dce50a6e3c58ae1a2460ef60901d40e1155d633c7392f858", + "sha256:c644ab3f221c7faaab2d1ccd11bc3b1106f172e9bb1c85a863b0a097f6b71cce", + "sha256:c95c0818c163b69989c9e876dd82005e60edfbaabfd45429abebfc26f9a357e8", + "sha256:cdd68e684f0c6e18604d46ee04dbcfe5c79de62238b2c29f1db0f3a5d8dfa47b", + "sha256:ce86c6dce2c923bfb16e26586bc5f0443a8be61d4f43227be8587ccb95588a46", + "sha256:e61d3c6b1b66072f5b74d46dbee7df29daac6ce9738b9a6223a67dc577114515", + "sha256:f8edf5a546b31afdcd801b60448ea890ce1ff418fb784335e1329519f13aa85e" + ], + "version": "==3.7.4" + }, "hatanaka": { "hashes": [ "sha256:0e095d35ed4f607eb77ae47ecb310e4c25f5a6267037b703ea258ed03e5c47da", @@ -327,7 +366,7 @@ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4' and python_full_version >= '3.6.1'", + "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -340,11 +379,11 @@ }, "jinja2": { "hashes": [ - "sha256:539835f51a74a69f41b848a9645dbdc35b4f20a3b601e2d9a7e22947b15ff119", - "sha256:640bed4bb501cbd17194b3cace1dc2126f5b619cf068a726b98192a0fde74ae9" + "sha256:31351a702a408a9e7595a8fc6150fc3f43bb6bf7e319770cbc0db9df9437e852", + "sha256:6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61" ], "index": "pypi", - "version": "==3.1.1" + "version": "==3.1.2" }, "json-rpc": { "hashes": [ @@ -576,16 +615,16 @@ }, "onnxruntime-gpu": { "hashes": [ - "sha256:2886a84a0e64f7ec594f787c0c941c05af230e5e3df342dd05d86382722dd78a", - "sha256:2db2bdcb23b6b4fa08a03009bf057f42cebf6828cb418f4f5ab890cc6d1bb8ff", - "sha256:58e9a3487820728e2140523787f0c413518f7f8ca137a7c3e015044b65d159f4", - "sha256:63f8b8e48f33b61f7bdec9a561770a6bea5ec3c905ef088e70cb5909c88e7515", - "sha256:766c1249c6a2fc422022348a04f747008cf171edd00c9a452454f7c35899ae88", - "sha256:fe00066d2d350806c1099761d856ec2934ff9843c192dee6d41cbe074ad5a1a9" + "sha256:3f1363e9ba30051cc3d649beefbd12047e1c41b5c47bcacfbfb23b74a7d68f7b", + "sha256:3fad0d3df58815c11160714433ca3bcff6d9a06f721bcc97ade46abce30aea72", + "sha256:a4f5317838f4816a9b21fcb43d551ac95f9d35ca8ecd5c959419b3b94d458342", + "sha256:be1766a9d60ec774e1a7a0279ade5ec001c5d528f2f2dbe9f8d02133e49d1d68", + "sha256:c79f42cbdee18e059c0ba43f0efeb7117539dfb76d6ed0e4a9ecc34093ed97b3", + "sha256:dc34be44224aa855d7ab17f61942b665788a2136ae4f71ee857fa47b38d1fdb8" ], "index": "pypi", "markers": "platform_system != 'Darwin'", - "version": "==1.11.0" + "version": "==1.11.1" }, "pillow": { "hashes": [ @@ -633,41 +672,41 @@ }, "platformdirs": { "hashes": [ - "sha256:7535e70dfa32e84d4b34996ea99c5e432fa29a708d0f4e394bbcb2a8faa4f16d", - "sha256:bcae7cab893c2d310a711b70b24efb93334febe65f8de776ee320b517471e227" + "sha256:027d8e83a2d7de06bbac4e5ef7e023c02b863d7ea5d079477e722bb41ab25788", + "sha256:58c8abb07dcb441e6ee4b11d8df0ac856038f944ab98b7be6b27b2a3c7feef19" ], "markers": "python_version >= '3.7'", - "version": "==2.5.1" + "version": "==2.5.2" }, "protobuf": { "hashes": [ - "sha256:001c2160c03b6349c04de39cf1a58e342750da3632f6978a1634a3dcca1ec10e", - "sha256:0b250c60256c8824219352dc2a228a6b49987e5bf94d3ffcf4c46585efcbd499", - "sha256:1d24c81c2310f0063b8fc1c20c8ed01f3331be9374b4b5c2de846f69e11e21fb", - "sha256:1eb13f5a5a59ca4973bcfa2fc8fff644bd39f2109c3f7a60bd5860cb6a49b679", - "sha256:25d2fcd6eef340082718ec9ad2c58d734429f2b1f7335d989523852f2bba220b", - "sha256:32bf4a90c207a0b4e70ca6dd09d43de3cb9898f7d5b69c2e9e3b966a7f342820", - "sha256:38fd9eb74b852e4ee14b16e9670cd401d147ee3f3ec0d4f7652e0c921d6227f8", - "sha256:47257d932de14a7b6c4ae1b7dbf592388153ee35ec7cae216b87ae6490ed39a3", - "sha256:4eda68bd9e2a4879385e6b1ea528c976f59cd9728382005cc54c28bcce8db983", - "sha256:52bae32a147c375522ce09bd6af4d2949aca32a0415bc62df1456b3ad17c6001", - "sha256:542f25a4adf3691a306dcc00bf9a73176554938ec9b98f20f929a044f80acf1b", - "sha256:5b5860b790498f233cdc8d635a17fc08de62e59d4dcd8cdb6c6c0d38a31edf2b", - "sha256:6efe066a7135233f97ce51a1aa007d4fb0be28ef093b4f88dac4ad1b3a2b7b6f", - "sha256:71b2c3d1cd26ed1ec7c8196834143258b2ad7f444efff26fdc366c6f5e752702", - "sha256:7a53d4035427b9dbfbb397f46642754d294f131e93c661d056366f2a31438263", - "sha256:7dcd84dc31ebb35ade755e06d1561d1bd3b85e85dbdbf6278011fc97b22810db", - "sha256:88c8be0558bdfc35e68c42ae5bf785eb9390d25915d4863bbc7583d23da77074", - "sha256:8be43a91ab66fe995e85ccdbdd1046d9f0443d59e060c0840319290de25b7d33", - "sha256:8d84453422312f8275455d1cb52d850d6a4d7d714b784e41b573c6f5bfc2a029", - "sha256:9d0f3aca8ca51c8b5e204ab92bd8afdb2a8e3df46bd0ce0bd39065d79aabcaa4", - "sha256:a1eebb6eb0653e594cb86cd8e536b9b083373fca9aba761ade6cd412d46fb2ab", - "sha256:bc14037281db66aa60856cd4ce4541a942040686d290e3f3224dd3978f88f554", - "sha256:fbcbb068ebe67c4ff6483d2e2aa87079c325f8470b24b098d6bf7d4d21d57a69", - "sha256:fd7133b885e356fa4920ead8289bb45dc6f185a164e99e10279f33732ed5ce15" + "sha256:06059eb6953ff01e56a25cd02cca1a9649a75a7e65397b5b9b4e929ed71d10cf", + "sha256:097c5d8a9808302fb0da7e20edf0b8d4703274d140fd25c5edabddcde43e081f", + "sha256:284f86a6207c897542d7e956eb243a36bb8f9564c1742b253462386e96c6b78f", + "sha256:32ca378605b41fd180dfe4e14d3226386d8d1b002ab31c969c366549e66a2bb7", + "sha256:3cc797c9d15d7689ed507b165cd05913acb992d78b379f6014e013f9ecb20996", + "sha256:62f1b5c4cd6c5402b4e2d63804ba49a327e0c386c99b1675c8a0fefda23b2067", + "sha256:69ccfdf3657ba59569c64295b7d51325f91af586f8d5793b734260dfe2e94e2c", + "sha256:6f50601512a3d23625d8a85b1638d914a0970f17920ff39cec63aaef80a93fb7", + "sha256:7403941f6d0992d40161aa8bb23e12575637008a5a02283a930addc0508982f9", + "sha256:755f3aee41354ae395e104d62119cb223339a8f3276a0cd009ffabfcdd46bb0c", + "sha256:77053d28427a29987ca9caf7b72ccafee011257561259faba8dd308fda9a8739", + "sha256:7e371f10abe57cee5021797126c93479f59fccc9693dafd6bd5633ab67808a91", + "sha256:9016d01c91e8e625141d24ec1b20fed584703e527d28512aa8c8707f105a683c", + "sha256:9be73ad47579abc26c12024239d3540e6b765182a91dbc88e23658ab71767153", + "sha256:adc31566d027f45efe3f44eeb5b1f329da43891634d61c75a5944e9be6dd42c9", + "sha256:adfc6cf69c7f8c50fd24c793964eef18f0ac321315439d94945820612849c388", + "sha256:af0ebadc74e281a517141daad9d0f2c5d93ab78e9d455113719a45a49da9db4e", + "sha256:cb29edb9eab15742d791e1025dd7b6a8f6fcb53802ad2f6e3adcb102051063ab", + "sha256:cd68be2559e2a3b84f517fb029ee611546f7812b1fdd0aa2ecc9bc6ec0e4fdde", + "sha256:cdee09140e1cd184ba9324ec1df410e7147242b94b5f8b0c64fc89e38a8ba531", + "sha256:db977c4ca738dd9ce508557d4fce0f5aebd105e158c725beec86feb1f6bc20d8", + "sha256:dd5789b2948ca702c17027c84c2accb552fc30f4622a98ab5c51fcfe8c50d3e7", + "sha256:e250a42f15bf9d5b09fe1b293bdba2801cd520a9f5ea2d7fb7536d4441811d20", + "sha256:ff8d8fa42675249bb456f5db06c00de6c2f4c27a065955917b28c4f15978b9c3" ], "markers": "python_version >= '3.7'", - "version": "==3.20.0" + "version": "==3.20.1" }, "psutil": { "hashes": [ @@ -795,24 +834,26 @@ }, "pylint": { "hashes": [ - "sha256:7cc6d0c4f61dff440f9ed8b657f4ecd615dcfe35345953eb7b1dc74afe901d7a", - "sha256:8672cf7441b81410f5de7defdf56e2d559c956fd0579652f2e0a0a35bea2d546" + "sha256:ced8968c3b699df0615e2a709554dec3ddac2f5cd06efadb69554a69eeca364a", + "sha256:f87e863a0b08f64b5230e7e779bcb75276346995737b2c0dc2793070487b1ff6" ], "index": "pypi", - "version": "==2.13.4" + "version": "==2.13.8" }, "pyopencl": { "hashes": [ - "sha256:1ab792ff11a7ff271b1ba39686bd7aae271168e813a7e771bff6aa611ada383b", - "sha256:24c6d9a0a1ff7609f3d7365ebd8778616a5433c426566c2c8e35ffab00ef22c4", - "sha256:3b3f0d8b69923064f6d64b520c594aa2506e96ab398a0f1ed4895c4fceb20ff4", - "sha256:4bea0e965252f477204a87cc73eca492de5c30252198bc6679ef4968880a2443", - "sha256:7d9ec6c8daf283666dd577d6bcc49ab3d5b44c9532c2f642daf7e9c85b73606f", - "sha256:d8af9c4ea375f51237059124f7bab1fd32e32a8893997ffa05dff88efc4d9274", - "sha256:dee72b29c4e47a99f5ecc7fc7ba70bfc3d85e3cc9734765d6992380f5296787b" + "sha256:0af2271c5b3d937290d2edb82c8cc0eca7916bb6321348b261454720bf2c9b8c", + "sha256:18386938b54855696460b4b19a210300f241a28eb3255748be5f279aef664d6d", + "sha256:2b7daa78caa3ef2ff592c01b4cd9a354ad91218a45da1bdfbb59fca4ea3fb209", + "sha256:32fb3e320ab22afa1680d7cc4f2269fa8a83decc7de286533f466188260d3910", + "sha256:33ee0d0fb726c029a745f21c2619c3747da6d14d95500c02e1e97b38e4060a38", + "sha256:439374ca364d00e0a93ee9656d4da1d5ce57616350a6433efb981a174d583b24", + "sha256:828eb7fa5e6ce3a98ae0d2a230fd6f68a8f631a089fefff5c1583e8f05103129", + "sha256:945d331dcbe2c868b32ceb0ad2ab245ecf943f5daa33eca04c88988c0e50cf65", + "sha256:acd3c817b61058c6056dc67738063dbb021db1fea995c9d5426fb325e58e9ce6" ], "index": "pypi", - "version": "==2022.1" + "version": "==2022.1.3" }, "pyserial": { "hashes": [ @@ -832,10 +873,10 @@ }, "pytools": { "hashes": [ - "sha256:5e824101880a246354756365880a65bb416f6a8cab6513b68fcbb48fba090fcb" + "sha256:9083e8b6e617560eebb7e0c22c01545b1599eb1c048fe72ca2796f22c040a317" ], "markers": "python_version ~= '3.6'", - "version": "==2022.1.2" + "version": "==2022.1.7" }, "pyyaml": { "hashes": [ @@ -947,46 +988,96 @@ }, "sentry-sdk": { "hashes": [ - "sha256:32af1a57954576709242beb8c373b3dbde346ac6bd616921def29d68846fb8c3", - "sha256:38fd16a92b5ef94203db3ece10e03bdaa291481dd7e00e77a148aa0302267d47" + "sha256:6c01d9d0b65935fd275adc120194737d1df317dce811e642cbf0394d0d37a007", + "sha256:c17179183cac614e900cbd048dab03f49a48e2820182ec686c25e7ce46f8548f" ], "index": "pypi", - "version": "==1.5.8" + "version": "==1.5.11" }, "setproctitle": { "hashes": [ - "sha256:077943272d0490b3f43d17379432d5e49c263f608fdf4cf624b419db762ca72b", - "sha256:0d160d46c8f3567e0aa27b26b1f36e03122e3de475aacacc14a92b8fe45b648a", - "sha256:0df728d0d350e6b1ad8436cc7add052faebca6f4d03257182d427d86d4422065", - "sha256:17598f38be9ef499d74f2380bf76b558be72e87da75d66b153350e586649171b", - "sha256:249526a06f16d493a2cb632abc1b1fdfaaa05776339a50dd9f27c941f6ff1383", - "sha256:28b884e1cb9a53974e15838864283f9bad774b5c7db98c9609416bd123cb9fd1", - "sha256:30bc7a769a4451639a0adcbc97bdf7a6e9ac0ef3ddad8d63eb1e338edb3ebeda", - "sha256:3f6136966c81daaf5b4b010613fe33240a045a4036132ef040b623e35772d998", - "sha256:4fc5bebd34f451dc87d2772ae6093adea1ea1dc29afc24641b250140decd23bb", - "sha256:5260e8700c5793d48e79c5e607e8e552e795b698491a4b9bb9111eb74366a450", - "sha256:7dfb472c8852403d34007e01d6e3c68c57eb66433fb8a5c77b13b89a160d97df", - "sha256:9106bcbacae534b6f82955b176723f1b2ca6514518aab44dffec05a583f8dca8", - "sha256:970798d948f0c90a3eb0f8750f08cb215b89dcbee1b55ffb353ad62d9361daeb", - "sha256:a11d329f33221443317e2aeaee9442f22fcae25be3aa4fb8489e4f7b1f65cdd2", - "sha256:ba1fb32e7267330bd9f72e69e076777a877f1cb9be5beac5e62d1279e305f37f", - "sha256:bc4393576ed3ac87ddac7d1bd0faaa2fab24840a025cc5f3c21d14cf0c9c8a12", - "sha256:c611f65bc9de5391a1514de556f71101e6531bb0715d240efd3e9732626d5c9e", - "sha256:e13a5c1d9c369cb11cdfc4b75be432b83eb3205c95a69006008ffd4366f87b9e", - "sha256:e696c93d93c23f377ccd2d72e38908d3dbfc90e45561602b805f53f2627d42ea", - "sha256:e8ef655eab26e83ec105ce79036bb87e5f2bf8ba2d6f48afdd9595ef7647fcf4", - "sha256:fbf914179dc4540ee6bfd8228b4cc1f1f6fb12dad66b72b5c9b955b222403220" - ], - "index": "pypi", - "version": "==1.2.2" + "sha256:01cef383afc7ea7a3b1696818c8712029bf2f1d64f5d4777dbaf0166becf2c00", + "sha256:0670f2130a7ca0e167d3d5a7c8e3c707340b8693d6af7416ff55c18ab2a0a43f", + "sha256:06aab65e68163ead9d046b452dd9ad1fc6834ce6bde490f63fdce3be53e9cc73", + "sha256:0a668acec8b61a971de54bc4c733869ea7b0eb1348eae5a32b9477f788908e5c", + "sha256:0b207de9e4f4aa5265b36dd826a1f6ef6566b064a042033bd7447efb7e9a7664", + "sha256:0b444ed4051161a3b0a85dec2bb9b50922f37c75f5fb86f7784b235cf6754336", + "sha256:138bfa853e607f06d95b0f253e9152b32a00af3d0dbec96abf0871236a483932", + "sha256:14641a4ec2f2110cf4afc666eaecc82ba67814e927e02647fa1f4cf74476e752", + "sha256:21d6e064b8fee4e58eb00cdd8771c638de1bc30bb6c02d0208af9ca0a1c00898", + "sha256:25538341e56f9e75e9759229ff674282dccb5b1ce79a974f968d36208d465674", + "sha256:28e0df80d5069586a08a3cb463fb23503a37cbb805826ef93164bc4bfb5f35b9", + "sha256:2c0be45535e934deab3aa72ed1a8487174af4ea12cec124478c68a312e1c8b13", + "sha256:2c8c245e08f6a296fdaa1b36894ec40e20464a4fc6458e6178c8d55a2f83457a", + "sha256:2d083cae02e344e760bd21c28d591ac5f7ddbd6e1a0ecba62092ae724abd5c28", + "sha256:32a84cc309b9e595f06a55bec2fa335a23c307a55d2989864b60ecd71ea87897", + "sha256:335750c9eb5b18326a138a09266862a52b4f474277c3e410b419bea9a1df8bee", + "sha256:35b869e416a105c59133a48b569c6e808159485d916f55e80c7394a42667a386", + "sha256:38855b06a124361dc73c198853dee3f2b775531c4f4b7472f0e3d441192b3d8a", + "sha256:3b1883ccdbee624386dc046cfbcd80c4e75e24c478f35627984a79892e088b88", + "sha256:3dbe87e76197f9a303451512088c18c96f09a6fc4f871a92e5bd695f46f94a26", + "sha256:3f55493c987935fa540ef9ffb7ee7db03b4a18a9d5cc103681e2e6a6dfbd7054", + "sha256:4051c3a3b07f8a4cca205cd45366a22f322da2f26491c0d6b313a10f8c77b734", + "sha256:409a39f92e123be061626fdfd3e76625b04db103479bb4ba1c85b587db0b9498", + "sha256:423f8a6d8116acf975ebf93d6b5c4a752f7d2039fa9aafe175a62de86e17016e", + "sha256:47f97f591ea2335b7d35f5e9ad7d806385338182dc6de5732d091e9c70ed1cc0", + "sha256:48ac48a94040ef21be37366cbc8270fcba2ca103d6c64da6099d5a7b034f72d0", + "sha256:4eed53c12146de5df959d84384ffc2774651cab406ee4854e12728cf0eee5297", + "sha256:501c084cf3df7d848e91c97d4f8c44d799ba545858a79c6960326ce6f285b4e4", + "sha256:52265182fe5ac237d179d8e949248d307882a2e6ec7f189c8dac1c9d1b3631fa", + "sha256:5464e6812d050c986e6e9b97d54ab88c23dbe9d81151a2fa10b48bb5133a1e2c", + "sha256:54c7315e53b49ef2227d47a75c3d28c4c51ea9ee46a066460732c0d0f8e605a7", + "sha256:60f7a2f5da36a3075dda7edbee2173be5b765b0460b8d401ee01a11f68dee1d2", + "sha256:65a9384cafdfed98f91416e93705ad08f049c298afcb9c515882beba23153bd0", + "sha256:71d00ef63a1f78e13c236895badac77b6c8503377467b9c1a4f81fe729d16e03", + "sha256:76f59444a25fb42ca07f53a4474b1545d97a06f016e6c6b8246eee5b146820b5", + "sha256:791bed39e4ecbdd008b64999a60c9cc560d17b3836ca0c27cd4708e8e1bcf495", + "sha256:7a72bbe53191fbe574c94c0f8b9451dce535b398b7c47ce2e26e21d55eaa1d7e", + "sha256:97accd117392b1e57e09888792750c403d7729b7e4b193005178b3736b325ea0", + "sha256:9a92978030616f5e20617b7b832efee398df82072b7239c53db41c8026f5fe55", + "sha256:9fb5d2e66f94eebc3d06cda9e71a3fffef24c5273971180a4b5628a37fae05a5", + "sha256:a39b30d7400c0d50941fe19e1fe0b7d35676186fec4d9c010129ac91b883fd26", + "sha256:a4a3cb19346a0cd680617742f5e39fdd14596f6fd91d6c9038272663e37441b4", + "sha256:a546cd2dfaecb227d24122257b98b2e062762871888835c7b608f1c41c3a77ad", + "sha256:a81067bdc015fee1cc148c79b346f24fdad1224a8898b4239c7cbdee1add8a60", + "sha256:a912df3f065572cef211e9ed9f157a0dd2bd73d150281f18f00728afa1b1e5d2", + "sha256:a993610383028f093112dce7f77b262e88fce9d70127535fcdc78953179857e8", + "sha256:b213376fc779c0e1a4b60008f3fd03f74e9baa9665db37fa6646e98d31baa6d8", + "sha256:b2fa9f4b382a6cf88f2f345044d0916a92f37cac21355585bd14bc7ee91af187", + "sha256:b9d905ac84dde5227de6516ec08639759f99684148bb88ba05f4cbdaebff5d69", + "sha256:be0b46beeb1c92450079a7f30a025d69b63fd6a5de040ebc478fd6e6bf3b63fc", + "sha256:c93a2272740e60cddf59d3e1d35dbb89fcc3676f5ca9618bb4e6ae9633fdf13c", + "sha256:ccb0b5334dbf248f7504d88b5e9e9a09a0da119eeafacd6f7247f7c055443522", + "sha256:d312a170f539895c8093b5e68ba126aa131c9f0d00f6360410db27ec50bf7afa", + "sha256:d45dbe4171f8c27a515ecb4562f4cd9ef67d98474bea18e0c14dfbdc2b225050", + "sha256:d8e4da68d4d4ba46d4c5db6ae5eb61b11de9c520f25ae8334570f4d0018a8611", + "sha256:e24fa9251cc22ddb88ef183070063fdca826c9636381f1c4fb9d2a1dccb7c2a4", + "sha256:e2ac0ebd9c63c3d19f768966be2f771bf088bc7373c63ed6fcbb3444a30d0f62", + "sha256:e40c35564081983eab6a07f9eb5693867bc447b0edf9c61b69446223d6593814", + "sha256:e80fc59739a738b5c67afbbb9d1c238aa47b6d290c2ada872b15c819350ec5f8", + "sha256:eb06c1086cf8c8cf12ce45a02450befcb408dfd646d0ccb47d388fd6e73c333a", + "sha256:eb82a49aaf440232c762539ab3737b5174d31aba0141fd4bf4d8739c28d18624", + "sha256:ec7c3a27460ae7811e868e5494e3d8aee5012912744c48fa2d80b5e614b1b972", + "sha256:ecf28b1c07a799d76f4326e508157b71aeda07b84b90368ea451c0710dbd32c0", + "sha256:efb3001fd9e71d3ae939d826bf436f0446fd30a6ac01e0ce08cd7eb55ee5ac57", + "sha256:f06ff922254023eaabef6af6631f89e5f2f420cf0112865d57d7703f933d4e9f", + "sha256:f272b84d79bbe15af26ecf6f7c129bbe642f628866c9253659cdb519216f138f", + "sha256:f2a137984d3436f13e4bf7c8ca6f6f292df119c009c5e39556cabba4f4bfbf92", + "sha256:f47f6704880869d8e8f52efac2f2f60f5ed4cb9662b98fc1c7e916eefe76e61d", + "sha256:f9cf1098205c23fbcaaaef798afaff714fa9ffadf24166f5e85e6d16b9ef82a1", + "sha256:fc586f002fd5dd8695718e22a83771fd9f744f081a2b8e614bf6b5f44135964a", + "sha256:fdb2231db176e0848b757fc5d9bed08bc8a498b5b9abb8b640f39e9720f309fc" + ], + "index": "pypi", + "version": "==1.2.3" }, "setuptools": { "hashes": [ - "sha256:7999cbd87f1b6e1f33bf47efa368b224bed5e27b5ef2c4d46580186cbcb1a86a", - "sha256:a65e3802053e99fc64c6b3b29c11132943d5b8c8facbcc461157511546510967" + "sha256:26ead7d1f93efc0f8c804d9fafafbe4a44b179580a7105754b245155f9af05a8", + "sha256:47c7b0c0f8fc10eec4cf1e71c6fdadf8decaa74ffa087e68cd1c20db7ad6a592" ], "markers": "python_version >= '3.7'", - "version": "==62.0.0" + "version": "==62.1.0" }, "six": { "hashes": [ @@ -1014,11 +1105,11 @@ }, "timezonefinder": { "hashes": [ - "sha256:4545533086eb25cd7ba10b97785059acbababf4577ab1b4d5c2ab56642eadfea", - "sha256:a374570295a8dbd923630ce85f754e52578e288cb0a9cf575834415e84758352" + "sha256:90228f7bcf60388868ac95d3d6a8c9f710c766990909cb89dc39a893da7132ad", + "sha256:ce16831bc6349a82ca25ffc0e4c89df5bc5df29b286e5201701bce852f8e49f2" ], "index": "pypi", - "version": "==5.2.0" + "version": "==6.0.0" }, "tomli": { "hashes": [ @@ -1038,11 +1129,11 @@ }, "typing-extensions": { "hashes": [ - "sha256:1a9462dcc3347a79b1f1c0271fbe79e844580bb598bafa1ed208b94da3cdcd42", - "sha256:21c85e0fe4b9a155d0799430b0ad741cdce7e359660ccbd8b530613e8df88ce2" + "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", + "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.6'", - "version": "==4.1.1" + "markers": "python_version >= '3.7'", + "version": "==4.2.0" }, "urllib3": { "hashes": [ @@ -1069,81 +1160,81 @@ }, "werkzeug": { "hashes": [ - "sha256:3c5493ece8268fecdcdc9c0b112211acd006354723b280d643ec732b6d4063d6", - "sha256:f8e89a20aeabbe8a893c24a461d3ee5dad2123b05cc6abd73ceed01d39c3ae74" + "sha256:1ce08e8093ed67d638d63879fd1ba3735817f7a80de3674d293f5984f25fb6e6", + "sha256:72a4b735692dd3135217911cbeaa1be5fa3f62bffb8745c5215420a03dc55255" ], "markers": "python_version >= '3.7'", - "version": "==2.1.1" + "version": "==2.1.2" }, "wrapt": { "hashes": [ - "sha256:00108411e0f34c52ce16f81f1d308a571df7784932cc7491d1e94be2ee93374b", - "sha256:01f799def9b96a8ec1ef6b9c1bbaf2bbc859b87545efbecc4a78faea13d0e3a0", - "sha256:09d16ae7a13cff43660155383a2372b4aa09109c7127aa3f24c3cf99b891c330", - "sha256:14e7e2c5f5fca67e9a6d5f753d21f138398cad2b1159913ec9e9a67745f09ba3", - "sha256:167e4793dc987f77fd476862d32fa404d42b71f6a85d3b38cbce711dba5e6b68", - "sha256:1807054aa7b61ad8d8103b3b30c9764de2e9d0c0978e9d3fc337e4e74bf25faa", - "sha256:1f83e9c21cd5275991076b2ba1cd35418af3504667affb4745b48937e214bafe", - "sha256:21b1106bff6ece8cb203ef45b4f5778d7226c941c83aaaa1e1f0f4f32cc148cd", - "sha256:22626dca56fd7f55a0733e604f1027277eb0f4f3d95ff28f15d27ac25a45f71b", - "sha256:23f96134a3aa24cc50614920cc087e22f87439053d886e474638c68c8d15dc80", - "sha256:2498762814dd7dd2a1d0248eda2afbc3dd9c11537bc8200a4b21789b6df6cd38", - "sha256:28c659878f684365d53cf59dc9a1929ea2eecd7ac65da762be8b1ba193f7e84f", - "sha256:2eca15d6b947cfff51ed76b2d60fd172c6ecd418ddab1c5126032d27f74bc350", - "sha256:354d9fc6b1e44750e2a67b4b108841f5f5ea08853453ecbf44c81fdc2e0d50bd", - "sha256:36a76a7527df8583112b24adc01748cd51a2d14e905b337a6fefa8b96fc708fb", - "sha256:3a0a4ca02752ced5f37498827e49c414d694ad7cf451ee850e3ff160f2bee9d3", - "sha256:3a71dbd792cc7a3d772ef8cd08d3048593f13d6f40a11f3427c000cf0a5b36a0", - "sha256:3a88254881e8a8c4784ecc9cb2249ff757fd94b911d5df9a5984961b96113fff", - "sha256:47045ed35481e857918ae78b54891fac0c1d197f22c95778e66302668309336c", - "sha256:4775a574e9d84e0212f5b18886cace049a42e13e12009bb0491562a48bb2b758", - "sha256:493da1f8b1bb8a623c16552fb4a1e164c0200447eb83d3f68b44315ead3f9036", - "sha256:4b847029e2d5e11fd536c9ac3136ddc3f54bc9488a75ef7d040a3900406a91eb", - "sha256:59d7d92cee84a547d91267f0fea381c363121d70fe90b12cd88241bd9b0e1763", - "sha256:5a0898a640559dec00f3614ffb11d97a2666ee9a2a6bad1259c9facd01a1d4d9", - "sha256:5a9a1889cc01ed2ed5f34574c90745fab1dd06ec2eee663e8ebeefe363e8efd7", - "sha256:5b835b86bd5a1bdbe257d610eecab07bf685b1af2a7563093e0e69180c1d4af1", - "sha256:5f24ca7953f2643d59a9c87d6e272d8adddd4a53bb62b9208f36db408d7aafc7", - "sha256:61e1a064906ccba038aa3c4a5a82f6199749efbbb3cef0804ae5c37f550eded0", - "sha256:65bf3eb34721bf18b5a021a1ad7aa05947a1767d1aa272b725728014475ea7d5", - "sha256:6807bcee549a8cb2f38f73f469703a1d8d5d990815c3004f21ddb68a567385ce", - "sha256:68aeefac31c1f73949662ba8affaf9950b9938b712fb9d428fa2a07e40ee57f8", - "sha256:6915682f9a9bc4cf2908e83caf5895a685da1fbd20b6d485dafb8e218a338279", - "sha256:6d9810d4f697d58fd66039ab959e6d37e63ab377008ef1d63904df25956c7db0", - "sha256:729d5e96566f44fccac6c4447ec2332636b4fe273f03da128fff8d5559782b06", - "sha256:748df39ed634851350efa87690c2237a678ed794fe9ede3f0d79f071ee042561", - "sha256:763a73ab377390e2af26042f685a26787c402390f682443727b847e9496e4a2a", - "sha256:8323a43bd9c91f62bb7d4be74cc9ff10090e7ef820e27bfe8815c57e68261311", - "sha256:8529b07b49b2d89d6917cfa157d3ea1dfb4d319d51e23030664a827fe5fd2131", - "sha256:87fa943e8bbe40c8c1ba4086971a6fefbf75e9991217c55ed1bcb2f1985bd3d4", - "sha256:88236b90dda77f0394f878324cfbae05ae6fde8a84d548cfe73a75278d760291", - "sha256:891c353e95bb11abb548ca95c8b98050f3620a7378332eb90d6acdef35b401d4", - "sha256:89ba3d548ee1e6291a20f3c7380c92f71e358ce8b9e48161401e087e0bc740f8", - "sha256:8c6be72eac3c14baa473620e04f74186c5d8f45d80f8f2b4eda6e1d18af808e8", - "sha256:9a242871b3d8eecc56d350e5e03ea1854de47b17f040446da0e47dc3e0b9ad4d", - "sha256:9a3ff5fb015f6feb78340143584d9f8a0b91b6293d6b5cf4295b3e95d179b88c", - "sha256:9a5a544861b21e0e7575b6023adebe7a8c6321127bb1d238eb40d99803a0e8bd", - "sha256:9d57677238a0c5411c76097b8b93bdebb02eb845814c90f0b01727527a179e4d", - "sha256:9d8c68c4145041b4eeae96239802cfdfd9ef927754a5be3f50505f09f309d8c6", - "sha256:9d9fcd06c952efa4b6b95f3d788a819b7f33d11bea377be6b8980c95e7d10775", - "sha256:a0057b5435a65b933cbf5d859cd4956624df37b8bf0917c71756e4b3d9958b9e", - "sha256:a65bffd24409454b889af33b6c49d0d9bcd1a219b972fba975ac935f17bdf627", - "sha256:b0ed6ad6c9640671689c2dbe6244680fe8b897c08fd1fab2228429b66c518e5e", - "sha256:b21650fa6907e523869e0396c5bd591cc326e5c1dd594dcdccac089561cacfb8", - "sha256:b3f7e671fb19734c872566e57ce7fc235fa953d7c181bb4ef138e17d607dc8a1", - "sha256:b77159d9862374da213f741af0c361720200ab7ad21b9f12556e0eb95912cd48", - "sha256:bb36fbb48b22985d13a6b496ea5fb9bb2a076fea943831643836c9f6febbcfdc", - "sha256:d066ffc5ed0be00cd0352c95800a519cf9e4b5dd34a028d301bdc7177c72daf3", - "sha256:d332eecf307fca852d02b63f35a7872de32d5ba8b4ec32da82f45df986b39ff6", - "sha256:d808a5a5411982a09fef6b49aac62986274ab050e9d3e9817ad65b2791ed1425", - "sha256:d9bdfa74d369256e4218000a629978590fd7cb6cf6893251dad13d051090436d", - "sha256:db6a0ddc1282ceb9032e41853e659c9b638789be38e5b8ad7498caac00231c23", - "sha256:debaf04f813ada978d7d16c7dfa16f3c9c2ec9adf4656efdc4defdf841fc2f0c", - "sha256:f0408e2dbad9e82b4c960274214af533f856a199c9274bd4aff55d4634dedc33", - "sha256:f2f3bc7cd9c9fcd39143f11342eb5963317bd54ecc98e3650ca22704b69d9653" + "sha256:00b6d4ea20a906c0ca56d84f93065b398ab74b927a7a3dbd470f6fc503f95dc3", + "sha256:01c205616a89d09827986bc4e859bcabd64f5a0662a7fe95e0d359424e0e071b", + "sha256:02b41b633c6261feff8ddd8d11c711df6842aba629fdd3da10249a53211a72c4", + "sha256:07f7a7d0f388028b2df1d916e94bbb40624c59b48ecc6cbc232546706fac74c2", + "sha256:11871514607b15cfeb87c547a49bca19fde402f32e2b1c24a632506c0a756656", + "sha256:1b376b3f4896e7930f1f772ac4b064ac12598d1c38d04907e696cc4d794b43d3", + "sha256:21ac0156c4b089b330b7666db40feee30a5d52634cc4560e1905d6529a3897ff", + "sha256:257fd78c513e0fb5cdbe058c27a0624c9884e735bbd131935fd49e9fe719d310", + "sha256:2b39d38039a1fdad98c87279b48bc5dce2c0ca0d73483b12cb72aa9609278e8a", + "sha256:2cf71233a0ed05ccdabe209c606fe0bac7379fdcf687f39b944420d2a09fdb57", + "sha256:2fe803deacd09a233e4762a1adcea5db5d31e6be577a43352936179d14d90069", + "sha256:3232822c7d98d23895ccc443bbdf57c7412c5a65996c30442ebe6ed3df335383", + "sha256:34aa51c45f28ba7f12accd624225e2b1e5a3a45206aa191f6f9aac931d9d56fe", + "sha256:36f582d0c6bc99d5f39cd3ac2a9062e57f3cf606ade29a0a0d6b323462f4dd87", + "sha256:380a85cf89e0e69b7cfbe2ea9f765f004ff419f34194018a6827ac0e3edfed4d", + "sha256:40e7bc81c9e2b2734ea4bc1aceb8a8f0ceaac7c5299bc5d69e37c44d9081d43b", + "sha256:43ca3bbbe97af00f49efb06e352eae40434ca9d915906f77def219b88e85d907", + "sha256:4fcc4649dc762cddacd193e6b55bc02edca674067f5f98166d7713b193932b7f", + "sha256:5a0f54ce2c092aaf439813735584b9537cad479575a09892b8352fea5e988dc0", + "sha256:5a9a0d155deafd9448baff28c08e150d9b24ff010e899311ddd63c45c2445e28", + "sha256:5b02d65b9ccf0ef6c34cba6cf5bf2aab1bb2f49c6090bafeecc9cd81ad4ea1c1", + "sha256:60db23fa423575eeb65ea430cee741acb7c26a1365d103f7b0f6ec412b893853", + "sha256:642c2e7a804fcf18c222e1060df25fc210b9c58db7c91416fb055897fc27e8cc", + "sha256:6a9a25751acb379b466ff6be78a315e2b439d4c94c1e99cb7266d40a537995d3", + "sha256:6b1a564e6cb69922c7fe3a678b9f9a3c54e72b469875aa8018f18b4d1dd1adf3", + "sha256:6d323e1554b3d22cfc03cd3243b5bb815a51f5249fdcbb86fda4bf62bab9e164", + "sha256:6e743de5e9c3d1b7185870f480587b75b1cb604832e380d64f9504a0535912d1", + "sha256:709fe01086a55cf79d20f741f39325018f4df051ef39fe921b1ebe780a66184c", + "sha256:7b7c050ae976e286906dd3f26009e117eb000fb2cf3533398c5ad9ccc86867b1", + "sha256:7d2872609603cb35ca513d7404a94d6d608fc13211563571117046c9d2bcc3d7", + "sha256:7ef58fb89674095bfc57c4069e95d7a31cfdc0939e2a579882ac7d55aadfd2a1", + "sha256:80bb5c256f1415f747011dc3604b59bc1f91c6e7150bd7db03b19170ee06b320", + "sha256:81b19725065dcb43df02b37e03278c011a09e49757287dca60c5aecdd5a0b8ed", + "sha256:833b58d5d0b7e5b9832869f039203389ac7cbf01765639c7309fd50ef619e0b1", + "sha256:88bd7b6bd70a5b6803c1abf6bca012f7ed963e58c68d76ee20b9d751c74a3248", + "sha256:8ad85f7f4e20964db4daadcab70b47ab05c7c1cf2a7c1e51087bfaa83831854c", + "sha256:8c0ce1e99116d5ab21355d8ebe53d9460366704ea38ae4d9f6933188f327b456", + "sha256:8d649d616e5c6a678b26d15ece345354f7c2286acd6db868e65fcc5ff7c24a77", + "sha256:903500616422a40a98a5a3c4ff4ed9d0066f3b4c951fa286018ecdf0750194ef", + "sha256:9736af4641846491aedb3c3f56b9bc5568d92b0692303b5a305301a95dfd38b1", + "sha256:988635d122aaf2bdcef9e795435662bcd65b02f4f4c1ae37fbee7401c440b3a7", + "sha256:9cca3c2cdadb362116235fdbd411735de4328c61425b0aa9f872fd76d02c4e86", + "sha256:9e0fd32e0148dd5dea6af5fee42beb949098564cc23211a88d799e434255a1f4", + "sha256:9f3e6f9e05148ff90002b884fbc2a86bd303ae847e472f44ecc06c2cd2fcdb2d", + "sha256:a85d2b46be66a71bedde836d9e41859879cc54a2a04fad1191eb50c2066f6e9d", + "sha256:a9a52172be0b5aae932bef82a79ec0a0ce87288c7d132946d645eba03f0ad8a8", + "sha256:aa31fdcc33fef9eb2552cbcbfee7773d5a6792c137b359e82879c101e98584c5", + "sha256:b014c23646a467558be7da3d6b9fa409b2c567d2110599b7cf9a0c5992b3b471", + "sha256:b21bb4c09ffabfa0e85e3a6b623e19b80e7acd709b9f91452b8297ace2a8ab00", + "sha256:b5901a312f4d14c59918c221323068fad0540e34324925c8475263841dbdfe68", + "sha256:b9b7a708dd92306328117d8c4b62e2194d00c365f18eff11a9b53c6f923b01e3", + "sha256:d1967f46ea8f2db647c786e78d8cc7e4313dbd1b0aca360592d8027b8508e24d", + "sha256:d52a25136894c63de15a35bc0bdc5adb4b0e173b9c0d07a2be9d3ca64a332735", + "sha256:d77c85fedff92cf788face9bfa3ebaa364448ebb1d765302e9af11bf449ca36d", + "sha256:d79d7d5dc8a32b7093e81e97dad755127ff77bcc899e845f41bf71747af0c569", + "sha256:dbcda74c67263139358f4d188ae5faae95c30929281bc6866d00573783c422b7", + "sha256:ddaea91abf8b0d13443f6dac52e89051a5063c7d014710dcb4d4abb2ff811a59", + "sha256:dee0ce50c6a2dd9056c20db781e9c1cfd33e77d2d569f5d1d9321c641bb903d5", + "sha256:dee60e1de1898bde3b238f18340eec6148986da0455d8ba7848d50470a7a32fb", + "sha256:e2f83e18fe2f4c9e7db597e988f72712c0c3676d337d8b101f6758107c42425b", + "sha256:e3fb1677c720409d5f671e39bac6c9e0e422584e5f518bfd50aa4cbbea02433f", + "sha256:ee2b1b1769f6707a8a445162ea16dddf74285c3964f605877a20e38545c3c462", + "sha256:ee6acae74a2b91865910eef5e7de37dc6895ad96fa23603d1d27ea69df545015", + "sha256:ef3f72c9666bba2bab70d2a8b79f2c6d2c1a42a7f7e2b0ec83bb2f9e383950af" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==1.14.0" + "version": "==1.14.1" }, "zipp": { "hashes": [ @@ -1194,27 +1285,28 @@ }, "babel": { "hashes": [ - "sha256:ab49e12b91d937cd11f0b67cb259a57ab4ad2b59ac7a3b41d6c06c0ac5b0def9", - "sha256:bc0c176f9f6a994582230df350aa6e05ba2ebe4b3ac317eab29d9be5d2768da0" + "sha256:3f349e85ad3154559ac4930c3918247d319f21910d5ce4b25d439ed8693b98d2", + "sha256:98aeaca086133efb3e1e2aad0396987490c8425929ddbcfe0550184fdc54cd13" ], - "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", - "version": "==2.9.1" + "markers": "python_version >= '3.6'", + "version": "==2.10.1" }, "bcrypt": { "hashes": [ - "sha256:56e5da069a76470679f312a7d3d23deb3ac4519991a0361abc11da837087b61d", - "sha256:5b93c1726e50a93a033c36e5ca7fdcd29a5c7395af50a6892f5d9e7c6cfbfb29", - "sha256:63d4e3ff96188e5898779b6057878fecf3f11cfe6ec3b313ea09955d587ec7a7", - "sha256:81fec756feff5b6818ea7ab031205e1d323d8943d237303baca2c5f9c7846f34", - "sha256:a0584a92329210fcd75eb8a3250c5a941633f8bfaf2a18f81009b097732839b7", - "sha256:a67fb841b35c28a59cebed05fbd3e80eea26e6d75851f0574a9273c80f3e9b55", - "sha256:b589229207630484aefe5899122fb938a5b017b0f4349f769b8c13e78d99a8fd", - "sha256:c95d4cbebffafcdd28bd28bb4e25b31c50f6da605c81ffd9ad8a3d1b2ab7b1b6", - "sha256:cd1ea2ff3038509ea95f687256c46b79f5fc382ad0aa3664d200047546d511d1", - "sha256:cdcdcb3972027f83fe24a48b1e90ea4b584d35f1cc279d76de6fc4b13376239d" + "sha256:2b02d6bfc6336d1094276f3f588aa1225a598e27f8e3388f4db9948cb707b521", + "sha256:433c410c2177057705da2a9f2cd01dd157493b2a7ac14c8593a16b3dab6b6bfb", + "sha256:4e029cef560967fb0cf4a802bcf4d562d3d6b4b1bf81de5ec1abbe0f1adb027e", + "sha256:61bae49580dce88095d669226d5076d0b9d927754cedbdf76c6c9f5099ad6f26", + "sha256:6d2cb9d969bfca5bc08e45864137276e4c3d3d7de2b162171def3d188bf9d34a", + "sha256:7180d98a96f00b1050e93f5b0f556e658605dd9f524d0b0e68ae7944673f525e", + "sha256:7d9ba2e41e330d2af4af6b1b6ec9e6128e91343d0b4afb9282e54e5508f31baa", + "sha256:7ff2069240c6bbe49109fe84ca80508773a904f5a8cb960e02a977f7f519b129", + "sha256:88273d806ab3a50d06bc6a2fc7c87d737dd669b76ad955f449c43095389bc8fb", + "sha256:a2c46100e315c3a5b90fdc53e429c006c5f962529bc27e1dfd656292c20ccc40", + "sha256:cd43303d6b8a165c29ec6756afd169faba9396a9472cdff753fe9f19b96ce2fa" ], "markers": "python_version >= '3.6'", - "version": "==3.2.0" + "version": "==3.2.2" }, "breathe": { "hashes": [ @@ -1372,29 +1464,31 @@ }, "cryptography": { "hashes": [ - "sha256:0a3bf09bb0b7a2c93ce7b98cb107e9170a90c51a0162a20af1c61c765b90e60b", - "sha256:1f64a62b3b75e4005df19d3b5235abd43fa6358d5516cfc43d87aeba8d08dd51", - "sha256:32db5cc49c73f39aac27574522cecd0a4bb7384e71198bc65a0d23f901e89bb7", - "sha256:4881d09298cd0b669bb15b9cfe6166f16fc1277b4ed0d04a22f3d6430cb30f1d", - "sha256:4e2dddd38a5ba733be6a025a1475a9f45e4e41139d1321f412c6b360b19070b6", - "sha256:53e0285b49fd0ab6e604f4c5d9c5ddd98de77018542e88366923f152dbeb3c29", - "sha256:70f8f4f7bb2ac9f340655cbac89d68c527af5bb4387522a8413e841e3e6628c9", - "sha256:7b2d54e787a884ffc6e187262823b6feb06c338084bbe80d45166a1cb1c6c5bf", - "sha256:7be666cc4599b415f320839e36367b273db8501127b38316f3b9f22f17a0b815", - "sha256:8241cac0aae90b82d6b5c443b853723bcc66963970c67e56e71a2609dc4b5eaf", - "sha256:82740818f2f240a5da8dfb8943b360e4f24022b093207160c77cadade47d7c85", - "sha256:8897b7b7ec077c819187a123174b645eb680c13df68354ed99f9b40a50898f77", - "sha256:c2c5250ff0d36fd58550252f54915776940e4e866f38f3a7866d92b32a654b86", - "sha256:ca9f686517ec2c4a4ce930207f75c00bf03d94e5063cbc00a1dc42531511b7eb", - "sha256:d2b3d199647468d410994dbeb8cec5816fb74feb9368aedf300af709ef507e3e", - "sha256:da73d095f8590ad437cd5e9faf6628a218aa7c387e1fdf67b888b47ba56a17f0", - "sha256:e167b6b710c7f7bc54e67ef593f8731e1f45aa35f8a8a7b72d6e42ec76afd4b3", - "sha256:ea634401ca02367c1567f012317502ef3437522e2fc44a3ea1844de028fa4b84", - "sha256:ec6597aa85ce03f3e507566b8bcdf9da2227ec86c4266bd5e6ab4d9e0cc8dab2", - "sha256:f64b232348ee82f13aac22856515ce0195837f6968aeaa94a3d0353ea2ec06a6" - ], - "index": "pypi", - "version": "==36.0.2" + "sha256:093cb351031656d3ee2f4fa1be579a8c69c754cf874206be1d4cf3b542042804", + "sha256:0cc20f655157d4cfc7bada909dc5cc228211b075ba8407c46467f63597c78178", + "sha256:1b9362d34363f2c71b7853f6251219298124aa4cc2075ae2932e64c91a3e2717", + "sha256:1f3bfbd611db5cb58ca82f3deb35e83af34bb8cf06043fa61500157d50a70982", + "sha256:2bd1096476aaac820426239ab534b636c77d71af66c547b9ddcd76eb9c79e004", + "sha256:31fe38d14d2e5f787e0aecef831457da6cec68e0bb09a35835b0b44ae8b988fe", + "sha256:3b8398b3d0efc420e777c40c16764d6870bcef2eb383df9c6dbb9ffe12c64452", + "sha256:3c81599befb4d4f3d7648ed3217e00d21a9341a9a688ecdd615ff72ffbed7336", + "sha256:419c57d7b63f5ec38b1199a9521d77d7d1754eb97827bbb773162073ccd8c8d4", + "sha256:46f4c544f6557a2fefa7ac8ac7d1b17bf9b647bd20b16decc8fbcab7117fbc15", + "sha256:471e0d70201c069f74c837983189949aa0d24bb2d751b57e26e3761f2f782b8d", + "sha256:59b281eab51e1b6b6afa525af2bd93c16d49358404f814fe2c2410058623928c", + "sha256:731c8abd27693323b348518ed0e0705713a36d79fdbd969ad968fbef0979a7e0", + "sha256:95e590dd70642eb2079d280420a888190aa040ad20f19ec8c6e097e38aa29e06", + "sha256:a68254dd88021f24a68b613d8c51d5c5e74d735878b9e32cc0adf19d1f10aaf9", + "sha256:a7d5137e556cc0ea418dca6186deabe9129cee318618eb1ffecbd35bee55ddc1", + "sha256:aeaba7b5e756ea52c8861c133c596afe93dd716cbcacae23b80bc238202dc023", + "sha256:dc26bb134452081859aa21d4990474ddb7e863aa39e60d1592800a8865a702de", + "sha256:e53258e69874a306fcecb88b7534d61820db8a98655662a3dd2ec7f1afd9132f", + "sha256:ef15c2df7656763b4ff20a9bc4381d8352e6640cfeb95c2972c38ef508e75181", + "sha256:f224ad253cc9cea7568f49077007d2263efa57396a2f2f78114066fd54b5c68e", + "sha256:f8ec91983e638a9bcd75b39f1396e5c0dc2330cbd9ce4accefe68717e6779e0a" + ], + "index": "pypi", + "version": "==37.0.2" }, "cycler": { "hashes": [ @@ -1488,11 +1582,11 @@ }, "fonttools": { "hashes": [ - "sha256:236b29aee6b113e8f7bee28779c1230a86ad2aac9a74a31b0aedf57e7dfb62a4", - "sha256:2df636a3f402ef14593c6811dac0609563b8c374bd7850e76919eb51ea205426" + "sha256:c0fdcfa8ceebd7c1b2021240bd46ef77aa8e7408cf10434be55df52384865f8e", + "sha256:f829c579a8678fa939a1d9e9894d01941db869de44390adb49ce67055a06cc2a" ], "markers": "python_version >= '3.7'", - "version": "==4.31.2" + "version": "==4.33.3" }, "hexdump": { "hashes": [ @@ -1503,19 +1597,19 @@ }, "hypothesis": { "hashes": [ - "sha256:ca931c5a6414f3f9636fdaf978a216ee9b5c4a6b4415adf628e9d5e5003dcd99", - "sha256:de48abb676fc76e4397cd002926e5747cef518570d132221244d27e1075c0bec" + "sha256:37ca37f61939d0a92c18b5e17ab8088dccc5fc077c913d6619bbe1d233dfca1e", + "sha256:c671b3801527f3a8189314d9385418a67d4c7ab1b3330a3ff8b267d0d4599b3d" ], "index": "pypi", - "version": "==6.41.0" + "version": "==6.46.2" }, "identify": { "hashes": [ - "sha256:3f3244a559290e7d3deb9e9adc7b33594c1bc85a9dd82e0f1be519bf12a1ec17", - "sha256:5f06b14366bd1facb88b00540a1de05b69b310cbc2654db3c7e07fa3a4339323" + "sha256:3acfe15a96e4272b4ec5662ee3e231ceba976ef63fd9980ed2ce9cc415df393f", + "sha256:c83af514ea50bf2be2c4a3f2fb349442b59dc87284558ae9ff54191bff3541d2" ], "markers": "python_version >= '3.7'", - "version": "==2.4.12" + "version": "==2.5.0" }, "idna": { "hashes": [ @@ -1558,11 +1652,11 @@ }, "jinja2": { "hashes": [ - "sha256:539835f51a74a69f41b848a9645dbdc35b4f20a3b601e2d9a7e22947b15ff119", - "sha256:640bed4bb501cbd17194b3cace1dc2126f5b619cf068a726b98192a0fde74ae9" + "sha256:31351a702a408a9e7595a8fc6150fc3f43bb6bf7e319770cbc0db9df9437e852", + "sha256:6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61" ], "index": "pypi", - "version": "==3.1.1" + "version": "==3.1.2" }, "kiwisolver": { "hashes": [ @@ -1622,11 +1716,11 @@ }, "markdown-it-py": { "hashes": [ - "sha256:31974138ca8cafbcb62213f4974b29571b940e78364584729233f59b8dfdb8bd", - "sha256:7b5c153ae1ab2cde00a33938bce68f3ad5d68fbe363f946de7d28555bed4e08a" + "sha256:93de681e5c021a432c63147656fe21790bc01231e0cd2da73626f1aa3ac0fe27", + "sha256:cf7e59fed14b5ae17c0006eff14a2d9a00ed5f3a846148153899a0224e2c07da" ], "index": "pypi", - "version": "==2.0.1" + "version": "==2.1.0" }, "markupsafe": { "hashes": [ @@ -1676,44 +1770,44 @@ }, "matplotlib": { "hashes": [ - "sha256:14334b9902ec776461c4b8c6516e26b450f7ebe0b3ef8703bf5cdfbbaecf774a", - "sha256:2252bfac85cec7af4a67e494bfccf9080bcba8a0299701eab075f48847cca907", - "sha256:2e3484d8455af3fdb0424eae1789af61f6a79da0c80079125112fd5c1b604218", - "sha256:34a1fc29f8f96e78ec57a5eff5e8d8b53d3298c3be6df61e7aa9efba26929522", - "sha256:3e66497cd990b1a130e21919b004da2f1dc112132c01ac78011a90a0f9229778", - "sha256:40e0d7df05e8efe60397c69b467fc8f87a2affeb4d562fe92b72ff8937a2b511", - "sha256:456cc8334f6d1124e8ff856b42d2cc1c84335375a16448189999496549f7182b", - "sha256:506b210cc6e66a0d1c2bb765d055f4f6bc2745070fb1129203b67e85bbfa5c18", - "sha256:53273c5487d1c19c3bc03b9eb82adaf8456f243b97ed79d09dded747abaf1235", - "sha256:577ed20ec9a18d6bdedb4616f5e9e957b4c08563a9f985563a31fd5b10564d2a", - "sha256:6803299cbf4665eca14428d9e886de62e24f4223ac31ab9c5d6d5339a39782c7", - "sha256:68fa30cec89b6139dc559ed6ef226c53fd80396da1919a1b5ef672c911aaa767", - "sha256:6c094e4bfecd2fa7f9adffd03d8abceed7157c928c2976899de282f3600f0a3d", - "sha256:778d398c4866d8e36ee3bf833779c940b5f57192fa0a549b3ad67bc4c822771b", - "sha256:7a350ca685d9f594123f652ba796ee37219bf72c8e0fc4b471473d87121d6d34", - "sha256:87900c67c0f1728e6db17c6809ec05c025c6624dcf96a8020326ea15378fe8e7", - "sha256:8a77906dc2ef9b67407cec0bdbf08e3971141e535db888974a915be5e1e3efc6", - "sha256:8e70ae6475cfd0fad3816dcbf6cac536dc6f100f7474be58d59fa306e6e768a4", - "sha256:abf67e05a1b7f86583f6ebd01f69b693b9c535276f4e943292e444855870a1b8", - "sha256:b04fc29bcef04d4e2d626af28d9d892be6aba94856cb46ed52bcb219ceac8943", - "sha256:b19a761b948e939a9e20173aaae76070025f0024fc8f7ba08bef22a5c8573afc", - "sha256:b2e9810e09c3a47b73ce9cab5a72243a1258f61e7900969097a817232246ce1c", - "sha256:b71f3a7ca935fc759f2aed7cec06cfe10bc3100fadb5dbd9c435b04e557971e1", - "sha256:b8a4fb2a0c5afbe9604f8a91d7d0f27b1832c3e0b5e365f95a13015822b4cd65", - "sha256:bb1c613908f11bac270bc7494d68b1ef6e7c224b7a4204d5dacf3522a41e2bc3", - "sha256:d24e5bb8028541ce25e59390122f5e48c8506b7e35587e5135efcb6471b4ac6c", - "sha256:d70a32ee1f8b55eed3fd4e892f0286df8cccc7e0475c11d33b5d0a148f5c7599", - "sha256:e293b16cf303fe82995e41700d172a58a15efc5331125d08246b520843ef21ee", - "sha256:e2f28a07b4f82abb40267864ad7b3a4ed76f1b1663e81c7efc84a9b9248f672f", - "sha256:e3520a274a0e054e919f5b3279ee5dbccf5311833819ccf3399dab7c83e90a25", - "sha256:e3b6f3fd0d8ca37861c31e9a7cab71a0ef14c639b4c95654ea1dd153158bf0df", - "sha256:e486f60db0cd1c8d68464d9484fd2a94011c1ac8593d765d0211f9daba2bd535", - "sha256:e8c87cdaf06fd7b2477f68909838ff4176f105064a72ca9d24d3f2a29f73d393", - "sha256:edf5e4e1d5fb22c18820e8586fb867455de3b109c309cb4fce3aaed85d9468d1", - "sha256:fe8d40c434a8e2c68d64c6d6a04e77f21791a93ff6afe0dce169597c110d3079" - ], - "index": "pypi", - "version": "==3.5.1" + "sha256:03bbb3f5f78836855e127b5dab228d99551ad0642918ccbf3067fcd52ac7ac5e", + "sha256:24173c23d1bcbaed5bf47b8785d27933a1ac26a5d772200a0f3e0e38f471b001", + "sha256:2a0967d4156adbd0d46db06bc1a877f0370bce28d10206a5071f9ecd6dc60b79", + "sha256:2e8bda1088b941ead50caabd682601bece983cadb2283cafff56e8fcddbf7d7f", + "sha256:31fbc2af27ebb820763f077ec7adc79b5a031c2f3f7af446bd7909674cd59460", + "sha256:364e6bca34edc10a96aa3b1d7cd76eb2eea19a4097198c1b19e89bee47ed5781", + "sha256:3d8e129af95b156b41cb3be0d9a7512cc6d73e2b2109f82108f566dbabdbf377", + "sha256:44c6436868186564450df8fd2fc20ed9daaef5caad699aa04069e87099f9b5a8", + "sha256:48cf850ce14fa18067f2d9e0d646763681948487a8080ec0af2686468b4607a2", + "sha256:49a5938ed6ef9dda560f26ea930a2baae11ea99e1c2080c8714341ecfda72a89", + "sha256:4a05f2b37222319753a5d43c0a4fd97ed4ff15ab502113e3f2625c26728040cf", + "sha256:4a44cdfdb9d1b2f18b1e7d315eb3843abb097869cd1ef89cfce6a488cd1b5182", + "sha256:4fa28ca76ac5c2b2d54bc058b3dad8e22ee85d26d1ee1b116a6fd4d2277b6a04", + "sha256:5844cea45d804174bf0fac219b4ab50774e504bef477fc10f8f730ce2d623441", + "sha256:5a32ea6e12e80dedaca2d4795d9ed40f97bfa56e6011e14f31502fdd528b9c89", + "sha256:6c623b355d605a81c661546af7f24414165a8a2022cddbe7380a31a4170fa2e9", + "sha256:751d3815b555dcd6187ad35b21736dc12ce6925fc3fa363bbc6dc0f86f16484f", + "sha256:75c406c527a3aa07638689586343f4b344fcc7ab1f79c396699eb550cd2b91f7", + "sha256:77157be0fc4469cbfb901270c205e7d8adb3607af23cef8bd11419600647ceed", + "sha256:7d7705022df2c42bb02937a2a824f4ec3cca915700dd80dc23916af47ff05f1a", + "sha256:7f409716119fa39b03da3d9602bd9b41142fab7a0568758cd136cd80b1bf36c8", + "sha256:9480842d5aadb6e754f0b8f4ebeb73065ac8be1855baa93cd082e46e770591e9", + "sha256:9776e1a10636ee5f06ca8efe0122c6de57ffe7e8c843e0fb6e001e9d9256ec95", + "sha256:a91426ae910819383d337ba0dc7971c7cefdaa38599868476d94389a329e599b", + "sha256:b4fedaa5a9aa9ce14001541812849ed1713112651295fdddd640ea6620e6cf98", + "sha256:b6c63cd01cad0ea8704f1fd586e9dc5777ccedcd42f63cbbaa3eae8dd41172a1", + "sha256:b8d3f4e71e26307e8c120b72c16671d70c5cd08ae412355c11254aa8254fb87f", + "sha256:c4b82c2ae6d305fcbeb0eb9c93df2602ebd2f174f6e8c8a5d92f9445baa0c1d3", + "sha256:c772264631e5ae61f0bd41313bbe48e1b9bcc95b974033e1118c9caa1a84d5c6", + "sha256:c87973ddec10812bddc6c286b88fdd654a666080fbe846a1f7a3b4ba7b11ab78", + "sha256:e2b696699386766ef171a259d72b203a3c75d99d03ec383b97fc2054f52e15cf", + "sha256:ea75df8e567743207e2b479ba3d8843537be1c146d4b1e3e395319a4e1a77fe9", + "sha256:ebc27ad11df3c1661f4677a7762e57a8a91dd41b466c3605e90717c9a5f90c82", + "sha256:ee0b8e586ac07f83bb2950717e66cb305e2859baf6f00a9c39cc576e0ce9629c", + "sha256:ee175a571e692fc8ae8e41ac353c0e07259113f4cb063b0ec769eff9717e84bb" + ], + "index": "pypi", + "version": "==3.5.2" }, "mdit-py-plugins": { "hashes": [ @@ -1725,11 +1819,11 @@ }, "mdurl": { "hashes": [ - "sha256:40654d6dcb8d21501ed13c21cc0bd6fc42ff07ceb8be30029e5ae63ebc2ecfda", - "sha256:94873a969008ee48880fb21bad7de0349fef529f3be178969af5817239e9b990" + "sha256:6a8f6804087b7128040b2fb2ebe242bdc2affaeaa034d5fc9feeed30b443651b", + "sha256:f79c9709944df218a4cdb0fcc0b0c7ead2f44594e3e84dc566606f04ad749c20" ], - "markers": "python_version >= '3.6'", - "version": "==0.1.0" + "markers": "python_version >= '3.7'", + "version": "==0.1.1" }, "mpld3": { "hashes": [ @@ -1742,32 +1836,32 @@ }, "mypy": { "hashes": [ - "sha256:0e2dd88410937423fba18e57147dd07cd8381291b93d5b1984626f173a26543e", - "sha256:10daab80bc40f84e3f087d896cdb53dc811a9f04eae4b3f95779c26edee89d16", - "sha256:17e44649fec92e9f82102b48a3bf7b4a5510ad0cd22fa21a104826b5db4903e2", - "sha256:1a0459c333f00e6a11cbf6b468b870c2b99a906cb72d6eadf3d1d95d38c9352c", - "sha256:246e1aa127d5b78488a4a0594bd95f6d6fb9d63cf08a66dafbff8595d8891f67", - "sha256:2b184db8c618c43c3a31b32ff00cd28195d39e9c24e7c3b401f3db7f6e5767f5", - "sha256:2bc249409a7168d37c658e062e1ab5173300984a2dada2589638568ddc1db02b", - "sha256:3841b5433ff936bff2f4dc8d54cf2cdbfea5d8e88cedfac45c161368e5770ba6", - "sha256:4c3e497588afccfa4334a9986b56f703e75793133c4be3a02d06a3df16b67a58", - "sha256:5bf44840fb43ac4074636fd47ee476d73f0039f4f54e86d7265077dc199be24d", - "sha256:64235137edc16bee6f095aba73be5334677d6f6bdb7fa03cfab90164fa294a17", - "sha256:6776e5fa22381cc761df53e7496a805801c1a751b27b99a9ff2f0ca848c7eca0", - "sha256:6ce34a118d1a898f47def970a2042b8af6bdcc01546454726c7dd2171aa6dfca", - "sha256:6f6ad963172152e112b87cc7ec103ba0f2db2f1cd8997237827c052a3903eaa6", - "sha256:6f7106cbf9cc2f403693bf50ed7c9fa5bb3dfa9007b240db3c910929abe2a322", - "sha256:7742d2c4e46bb5017b51c810283a6a389296cda03df805a4f7869a6f41246534", - "sha256:9521c1265ccaaa1791d2c13582f06facf815f426cd8b07c3a485f486a8ffc1f3", - "sha256:a1b383fe99678d7402754fe90448d4037f9512ce70c21f8aee3b8bf48ffc51db", - "sha256:b840cfe89c4ab6386c40300689cd8645fc8d2d5f20101c7f8bd23d15fca14904", - "sha256:d8d3ba77e56b84cd47a8ee45b62c84b6d80d32383928fe2548c9a124ea0a725c", - "sha256:dcd955f36e0180258a96f880348fbca54ce092b40fbb4b37372ae3b25a0b0a46", - "sha256:e865fec858d75b78b4d63266c9aff770ecb6a39dfb6d6b56c47f7f8aba6baba8", - "sha256:edf7237137a1a9330046dbb14796963d734dd740a98d5e144a3eb1d267f5f9ee" - ], - "index": "pypi", - "version": "==0.942" + "sha256:0112752a6ff07230f9ec2f71b0d3d4e088a910fdce454fdb6553e83ed0eced7d", + "sha256:0384d9f3af49837baa92f559d3fa673e6d2652a16550a9ee07fc08c736f5e6f8", + "sha256:1b333cfbca1762ff15808a0ef4f71b5d3eed8528b23ea1c3fb50543c867d68de", + "sha256:1fdeb0a0f64f2a874a4c1f5271f06e40e1e9779bf55f9567f149466fc7a55038", + "sha256:4c653e4846f287051599ed8f4b3c044b80e540e88feec76b11044ddc5612ffed", + "sha256:563514c7dc504698fb66bb1cf897657a173a496406f1866afae73ab5b3cdb334", + "sha256:5b231afd6a6e951381b9ef09a1223b1feabe13625388db48a8690f8daa9b71ff", + "sha256:5ce6a09042b6da16d773d2110e44f169683d8cc8687e79ec6d1181a72cb028d2", + "sha256:5e7647df0f8fc947388e6251d728189cfadb3b1e558407f93254e35abc026e22", + "sha256:6003de687c13196e8a1243a5e4bcce617d79b88f83ee6625437e335d89dfebe2", + "sha256:61504b9a5ae166ba5ecfed9e93357fd51aa693d3d434b582a925338a2ff57fd2", + "sha256:77423570c04aca807508a492037abbd72b12a1fb25a385847d191cd50b2c9605", + "sha256:a4d9898f46446bfb6405383b57b96737dcfd0a7f25b748e78ef3e8c576bba3cb", + "sha256:a952b8bc0ae278fc6316e6384f67bb9a396eb30aced6ad034d3a76120ebcc519", + "sha256:b5b5bd0ffb11b4aba2bb6d31b8643902c48f990cc92fda4e21afac658044f0c0", + "sha256:ca75ecf2783395ca3016a5e455cb322ba26b6d33b4b413fcdedfc632e67941dc", + "sha256:cf9c261958a769a3bd38c3e133801ebcd284ffb734ea12d01457cb09eacf7d7b", + "sha256:dd4d670eee9610bf61c25c940e9ade2d0ed05eb44227275cce88701fee014b1f", + "sha256:e19736af56947addedce4674c0971e5dceef1b5ec7d667fe86bcd2b07f8f9075", + "sha256:eaea21d150fb26d7b4856766e7addcf929119dd19fc832b22e71d942835201ef", + "sha256:eaff8156016487c1af5ffa5304c3e3fd183edcb412f3e9c72db349faf3f6e0eb", + "sha256:ee0a36edd332ed2c5208565ae6e3a7afc0eabb53f5327e281f2ef03a6bc7687a", + "sha256:ef7beb2a3582eb7a9f37beaf38a28acfd801988cde688760aea9e6cc4832b10b" + ], + "index": "pypi", + "version": "==0.950" }, "mypy-extensions": { "hashes": [ @@ -1778,11 +1872,11 @@ }, "myst-parser": { "hashes": [ - "sha256:555ec2950aba5ae5dac5c162c7e9a43ad4a7291cfac644d8f5f84da8efa6f356", - "sha256:d412347a5cacb77ebc03d7f7ffef050cd61957d46f234313d350e84e24972260" + "sha256:1635ce3c18965a528d6de980f989ff64d6a1effb482e1f611b1bfb79e38f3d98", + "sha256:4c076d649e066f9f5c7c661bae2658be1ca06e76b002bb97f02a09398707686c" ], "index": "pypi", - "version": "==0.17.0" + "version": "==0.17.2" }, "natsort": { "hashes": [ @@ -1856,11 +1950,11 @@ }, "paramiko": { "hashes": [ - "sha256:ac6593479f2b47a9422eca076b22cff9f795495e6733a64723efc75dd8c92101", - "sha256:ddb1977853aef82804b35d72a0e597b244fa326c404c350bd00c5b01dbfee71a" + "sha256:3c9ed6084f4b671ab66dc3c729092d32d96c3258f1426071301cb33654b09027", + "sha256:3d2e650b6812ce6d160abff701d6ef4434ec97934b13e95cf1ad3da70ffb5c58" ], "index": "pypi", - "version": "==2.10.3" + "version": "==2.10.4" }, "pillow": { "hashes": [ @@ -1908,11 +2002,11 @@ }, "platformdirs": { "hashes": [ - "sha256:7535e70dfa32e84d4b34996ea99c5e432fa29a708d0f4e394bbcb2a8faa4f16d", - "sha256:bcae7cab893c2d310a711b70b24efb93334febe65f8de776ee320b517471e227" + "sha256:027d8e83a2d7de06bbac4e5ef7e023c02b863d7ea5d079477e722bb41ab25788", + "sha256:58c8abb07dcb441e6ee4b11d8df0ac856038f944ab98b7be6b27b2a3c7feef19" ], "markers": "python_version >= '3.7'", - "version": "==2.5.1" + "version": "==2.5.2" }, "pluggy": { "hashes": [ @@ -1931,11 +2025,11 @@ }, "pre-commit": { "hashes": [ - "sha256:02226e69564ebca1a070bd1f046af866aa1c318dbc430027c50ab832ed2b73f2", - "sha256:5d445ee1fa8738d506881c5d84f83c62bb5be6b2838e32207433647e8e5ebe10" + "sha256:10c62741aa5704faea2ad69cb550ca78082efe5697d6f04e5710c3c229afdd10", + "sha256:4233a1e38621c87d9dda9808c6606d7e7ba0e087cd56d3fe03202a01d2919615" ], "index": "pypi", - "version": "==2.18.1" + "version": "==2.19.0" }, "py": { "hashes": [ @@ -2025,11 +2119,11 @@ }, "pygments": { "hashes": [ - "sha256:44238f1b60a76d78fc8ca0528ee429702aae011c265fe6a8dd8b63049ae41c65", - "sha256:4e426f72023d88d03b2fa258de560726ce890ff3b630f88c21cbb8b2503b8c6a" + "sha256:5eb116118f9612ff1ee89ac96437bb6b49e8f04d8a13b514ba26f620208e26eb", + "sha256:dc9c10fb40944260f6ed4c688ece0cd2048414940f1cea51b8b226318411c519" ], - "markers": "python_version >= '3.5'", - "version": "==2.11.2" + "markers": "python_version >= '3.6'", + "version": "==2.12.0" }, "pynacl": { "hashes": [ @@ -2049,11 +2143,11 @@ }, "pyparsing": { "hashes": [ - "sha256:18ee9022775d270c55187733956460083db60b37d0d0fb357445f3094eed3eea", - "sha256:a6c06a88f252e6c322f65faf8f418b16213b51bdfaece0524c1c1bc30c63c484" + "sha256:7bf433498c016c4314268d95df76c81b842a4cb2b276fa3312cfb1e1d85f6954", + "sha256:ef7b523f6356f763771559412c0d7134753f037822dad1b16945b7b846f7ad06" ], - "markers": "python_version >= '3.6'", - "version": "==3.0.7" + "markers": "python_full_version >= '3.6.8'", + "version": "==3.0.8" }, "pyprof2calltree": { "hashes": [ @@ -2064,11 +2158,11 @@ }, "pytest": { "hashes": [ - "sha256:841132caef6b1ad17a9afde46dc4f6cfa59a05f9555aae5151f73bdf2820ca63", - "sha256:92f723789a8fdd7180b6b06483874feca4c48a5c76968e03bb3e7f806a1869ea" + "sha256:13d0e3ccfc2b6e26be000cb6568c832ba67ba32e719443bfe725814d3c42433c", + "sha256:a06a0425453864a270bc45e71f783330a7428defb4230fb5e6a731fde06ecd45" ], "index": "pypi", - "version": "==7.1.1" + "version": "==7.1.2" }, "pytest-forked": { "hashes": [ @@ -2312,11 +2406,11 @@ }, "typing-extensions": { "hashes": [ - "sha256:1a9462dcc3347a79b1f1c0271fbe79e844580bb598bafa1ed208b94da3cdcd42", - "sha256:21c85e0fe4b9a155d0799430b0ad741cdce7e359660ccbd8b530613e8df88ce2" + "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", + "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.6'", - "version": "==4.1.1" + "markers": "python_version >= '3.7'", + "version": "==4.2.0" }, "urllib3": { "hashes": [ @@ -2328,11 +2422,11 @@ }, "virtualenv": { "hashes": [ - "sha256:1e8588f35e8b42c6ec6841a13c5e88239de1e6e4e4cedfd3916b306dc826ec66", - "sha256:8e5b402037287126e81ccde9432b95a8be5b19d36584f64957060a3488c11ca8" + "sha256:e617f16e25b42eb4f6e74096b9c9e37713cf10bf30168fb4a739f3fa8f898a3a", + "sha256:ef589a79795589aada0c1c5b319486797c03b67ac3984c48c669c0e4f50df3a5" ], "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3, 3.4'", - "version": "==20.14.0" + "version": "==20.14.1" }, "zipp": { "hashes": [ From ac1566b4c4571f7f99adf0ff198383fe975160c3 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 May 2022 18:50:10 -0700 Subject: [PATCH 072/391] cars: move common car info to subclass (#24481) * clean up values a bit and make HondaCarInfo for package * also move min_steer_speed which had 12 occurrences * odyssey has ALC down to 0 * do Nissan, Mazda, and Chrysler --- selfdrive/car/chrysler/values.py | 20 +++++++---- selfdrive/car/honda/values.py | 57 ++++++++++++++++++-------------- selfdrive/car/mazda/values.py | 20 +++++++---- selfdrive/car/nissan/values.py | 16 ++++++--- 4 files changed, 70 insertions(+), 43 deletions(-) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index cda15dbbdb..3716caf5bf 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,3 +1,4 @@ +from dataclasses import dataclass from typing import Dict, List, Union from selfdrive.car import dbc_dict @@ -22,13 +23,18 @@ class CAR: JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk -CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { - CAR.PACIFICA_2017_HYBRID: CarInfo("Chrysler Pacifica Hybrid 2017-18", "Adaptive Cruise"), - CAR.PACIFICA_2019_HYBRID: CarInfo("Chrysler Pacifica Hybrid 2019-21", "Adaptive Cruise"), - CAR.PACIFICA_2018: CarInfo("Chrysler Pacifica 2017-18", "Adaptive Cruise"), - CAR.PACIFICA_2020: CarInfo("Chrysler Pacifica 2020", "Adaptive Cruise"), - CAR.JEEP_CHEROKEE: CarInfo("Jeep Grand Cherokee 2016-18", "Adaptive Cruise", "https://www.youtube.com/watch?v=eLR9o2JkuRk"), - CAR.JEEP_CHEROKEE_2019: CarInfo("Jeep Grand Cherokee 2019-20", "Adaptive Cruise", "https://www.youtube.com/watch?v=jBe4lWnRSu4"), +@dataclass +class ChryslerCarInfo(CarInfo): + package: str = "Adaptive Cruise" + + +CAR_INFO: Dict[str, Union[ChryslerCarInfo, List[ChryslerCarInfo]]] = { + CAR.PACIFICA_2017_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2017-18"), + CAR.PACIFICA_2019_HYBRID: ChryslerCarInfo("Chrysler Pacifica Hybrid 2019-21"), + CAR.PACIFICA_2018: ChryslerCarInfo("Chrysler Pacifica 2017-18"), + CAR.PACIFICA_2020: ChryslerCarInfo("Chrysler Pacifica 2020"), + CAR.JEEP_CHEROKEE: ChryslerCarInfo("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk"), + CAR.JEEP_CHEROKEE_2019: ChryslerCarInfo("Jeep Grand Cherokee 2019-20", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4"), } # Unique CAN messages: diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index ab1f44ac87..fa369d1c9a 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -1,14 +1,16 @@ +from dataclasses import dataclass from enum import Enum, IntFlag from typing import Dict, List, Union from cereal import car +from common.conversions import Conversions as CV from selfdrive.car import dbc_dict from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column -from common.conversions import Conversions as CV Ecu = car.CarParams.Ecu VisualAlert = car.CarControl.HUDControl.VisualAlert + class CarControllerParams: # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we # perform the closed loop control, and might need some @@ -53,6 +55,7 @@ class CruiseButtons: CANCEL = 2 MAIN = 1 + # See dbc files for info on values VISUAL_HUD = { VisualAlert.none: 0, @@ -97,33 +100,39 @@ class Footnote(Enum): Column.FSR_STEERING) -CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { +@dataclass +class HondaCarInfo(CarInfo): + package: str = "Honda Sensing" + min_steer_speed: float = 12. * CV.MPH_TO_MS + + +CAR_INFO: Dict[str, Union[HondaCarInfo, List[HondaCarInfo]]] = { CAR.ACCORD: [ - CarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), - CarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), ], - CAR.ACCORDH: CarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.CIVIC: CarInfo("Honda Civic 2016-18", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), + CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), + CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18"), CAR.CIVIC_BOSCH: [ - CarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), - CarInfo("Honda Civic Hatchback 2017-21", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), + HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), + HondaCarInfo("Honda Civic Hatchback 2017-21"), ], - CAR.ACURA_ILX: CarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS), - CAR.CRV: CarInfo("Honda CR-V 2015-16", "Touring", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.CRV_5G: CarInfo("Honda CR-V 2017-21", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - # CAR.CRV_EU: CarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring - CAR.CRV_HYBRID: CarInfo("Honda CR-V Hybrid 2017-19", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.FIT: CarInfo("Honda Fit 2018-19", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.FREED: CarInfo("Honda Freed 2020", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.HRV: CarInfo("Honda HR-V 2019-20", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.ODYSSEY: CarInfo("Honda Odyssey 2018-20", "Honda Sensing"), - CAR.ACURA_RDX: CarInfo("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.ACURA_RDX_3G: CarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.PILOT: CarInfo("Honda Pilot 2016-21", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.PASSPORT: CarInfo("Honda Passport 2019-21", "All", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.RIDGELINE: CarInfo("Honda Ridgeline 2017-21", "Honda Sensing", min_steer_speed=12. * CV.MPH_TO_MS), - CAR.INSIGHT: CarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.HONDA_E: CarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS), + CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS), + CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring"), + CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21"), + # CAR.CRV_EU: HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring + CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19"), + CAR.FIT: HondaCarInfo("Honda Fit 2018-19"), + CAR.FREED: HondaCarInfo("Honda Freed 2020"), + CAR.HRV: HondaCarInfo("Honda HR-V 2019-20"), + CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0.), + CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus"), + CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), + CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21"), + CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All"), + CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-21"), + CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), + CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS), } diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 6b6aa05c29..a196b82a9e 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -1,3 +1,4 @@ +from dataclasses import dataclass from typing import Dict, List, Union from selfdrive.car import dbc_dict @@ -27,13 +28,18 @@ class CAR: CX5_2022 = "MAZDA CX-5 2022" -CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { - CAR.CX5: CarInfo("Mazda CX-5 2017, 2019", "All"), # TODO: verify years and torque for first 4 - CAR.CX9: CarInfo("Mazda CX-9 2016-17", "All"), - CAR.MAZDA3: CarInfo("Mazda 3 2017", "All"), - CAR.MAZDA6: CarInfo("Mazda 6 2017", "All"), - CAR.CX9_2021: CarInfo("Mazda CX-9 2021", "All", good_torque=True), - CAR.CX5_2022: CarInfo("Mazda CX-5 2022", "All", good_torque=True), +@dataclass +class MazdaCarInfo(CarInfo): + package: str = "All" + + +CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { + CAR.CX5: MazdaCarInfo("Mazda CX-5 2017, 2019"), # TODO: verify years and torque for first 4 + CAR.CX9: MazdaCarInfo("Mazda CX-9 2016-17"), + CAR.MAZDA3: MazdaCarInfo("Mazda 3 2017"), + CAR.MAZDA6: MazdaCarInfo("Mazda 6 2017"), + CAR.CX9_2021: MazdaCarInfo("Mazda CX-9 2021", good_torque=True), + CAR.CX5_2022: MazdaCarInfo("Mazda CX-5 2022", good_torque=True), } diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index a201c9113c..51ee7b5286 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -1,3 +1,4 @@ +from dataclasses import dataclass from typing import Dict, List, Union from selfdrive.car import dbc_dict @@ -24,11 +25,16 @@ class CAR: ALTIMA = "NISSAN ALTIMA 2020" -CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { - CAR.XTRAIL: CarInfo("Nissan X-Trail 2017", "ProPILOT"), - CAR.LEAF: CarInfo("Nissan Leaf 2018-22", "ProPILOT"), - CAR.ROGUE: CarInfo("Nissan Rogue 2018-20", "ProPILOT"), - CAR.ALTIMA: CarInfo("Nissan Altima 2019-20", "ProPILOT"), +@dataclass +class NissanCarInfo(CarInfo): + package: str = "ProPILOT" + + +CAR_INFO: Dict[str, Union[NissanCarInfo, List[NissanCarInfo]]] = { + CAR.XTRAIL: NissanCarInfo("Nissan X-Trail 2017"), + CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22"), + CAR.ROGUE: NissanCarInfo("Nissan Rogue 2018-20"), + CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20"), } FINGERPRINTS = { From e2ada3b9a8b990420929bc31df617a457e408910 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 May 2022 20:29:58 -0700 Subject: [PATCH 073/391] CARS.md: clicking stars doesn't change page location (#24482) --- docs/CARS.md | 352 ++++++++++++++++----------------- selfdrive/car/CARS_template.md | 2 +- 2 files changed, 177 insertions(+), 177 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 8a78afe5cb..02dfdedba1 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -12,25 +12,25 @@ How We Rate The Cars --- ### openpilot Adaptive Cruise Control (ACC) -- - openpilot is able to control the gas and brakes. -- - openpilot is able to control the gas and brakes with some restrictions. -- - The gas and brakes are controlled by the car's stock Adaptive Cruise Control (ACC) system. +- - openpilot is able to control the gas and brakes. +- - openpilot is able to control the gas and brakes with some restrictions. +- - The gas and brakes are controlled by the car's stock Adaptive Cruise Control (ACC) system. ### Stop and Go -- - Adaptive Cruise Control (ACC) operates down to 0 mph. -- - Adaptive Cruise Control (ACC) available only above certain speeds. See your car's manual for the minimum speed. +- - Adaptive Cruise Control (ACC) operates down to 0 mph. +- - Adaptive Cruise Control (ACC) available only above certain speeds. See your car's manual for the minimum speed. ### Steer to 0 -- - openpilot can control the steering wheel down to 0 mph. -- - No steering control below certain speeds. +- - openpilot can control the steering wheel down to 0 mph. +- - No steering control below certain speeds. ### Steering Torque -- - Car has enough steering torque for comfortable highway driving. -- - Limited ability to make turns. +- - Car has enough steering torque for comfortable highway driving. +- - Limited ability to make turns. ### Actively Maintained -- - Mainline software support, harness hardware sold by comma, lots of users, primary development target. -- - Low user count, community maintained, harness hardware not sold by comma. +- - Mainline software support, harness hardware sold by comma, lots of users, primary development target. +- - Low user count, community maintained, harness hardware not sold by comma. **All supported cars can move between the tiers as support changes.** @@ -38,181 +38,181 @@ How We Rate The Cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| -|comma|body|All|||||| -|Genesis|G70 2020|All|||||| -|Hyundai|Palisade 2020-21|All|||||| -|Hyundai|Santa Fe 2019-20|All|||||| -|Hyundai|Sonata 2020-22|All|||||| -|Hyundai|Sonata Hybrid 2020-22|All|||||| -|Kia|Niro Electric 2019-22|All|||||| -|Kia|Telluride 2020|SCC + LKAS|||||| -|Lexus|ES 2019-21|All|||||| -|Lexus|ES Hybrid 2019-22|All|||||| -|Lexus|NX 2020|All|||||| -|Lexus|RX 2020-22|All|||||| -|Lexus|RX Hybrid 2020-21|All|||||| -|Lexus|UX Hybrid 2019-21|All|||||| -|Toyota|Alphard 2019-20|All|||||| -|Toyota|Alphard Hybrid 2021|All|||||| -|Toyota|Avalon 2022|All|||||| -|Toyota|Avalon Hybrid 2022|All|||||| -|Toyota|Camry 2021-22|All||[4](#footnotes)|||| -|Toyota|Camry Hybrid 2021-22|All|||||| -|Toyota|Corolla 2020-22|All|||||| -|Toyota|Corolla Hatchback 2019-22|All|||||| -|Toyota|Corolla Hybrid 2020-22|All|||||| -|Toyota|Highlander 2020-22|All|||||| -|Toyota|Highlander Hybrid 2020-22|All|||||| -|Toyota|Mirai 2021|All|||||| -|Toyota|Prius 2021-22|All|||||| -|Toyota|Prius Prime 2021-22|All|||||| -|Toyota|RAV4 2019-21|All|||||| -|Toyota|RAV4 Hybrid 2019-21|All|||||| +|comma|body|All|||||| +|Genesis|G70 2020|All|||||| +|Hyundai|Palisade 2020-21|All|||||| +|Hyundai|Santa Fe 2019-20|All|||||| +|Hyundai|Sonata 2020-22|All|||||| +|Hyundai|Sonata Hybrid 2020-22|All|||||| +|Kia|Niro Electric 2019-22|All|||||| +|Kia|Telluride 2020|SCC + LKAS|||||| +|Lexus|ES 2019-21|All|||||| +|Lexus|ES Hybrid 2019-22|All|||||| +|Lexus|NX 2020|All|||||| +|Lexus|RX 2020-22|All|||||| +|Lexus|RX Hybrid 2020-21|All|||||| +|Lexus|UX Hybrid 2019-21|All|||||| +|Toyota|Alphard 2019-20|All|||||| +|Toyota|Alphard Hybrid 2021|All|||||| +|Toyota|Avalon 2022|All|||||| +|Toyota|Avalon Hybrid 2022|All|||||| +|Toyota|Camry 2021-22|All||[4](#footnotes)|||| +|Toyota|Camry Hybrid 2021-22|All|||||| +|Toyota|Corolla 2020-22|All|||||| +|Toyota|Corolla Hatchback 2019-22|All|||||| +|Toyota|Corolla Hybrid 2020-22|All|||||| +|Toyota|Highlander 2020-22|All|||||| +|Toyota|Highlander Hybrid 2020-22|All|||||| +|Toyota|Mirai 2021|All|||||| +|Toyota|Prius 2021-22|All|||||| +|Toyota|Prius Prime 2021-22|All|||||| +|Toyota|RAV4 2019-21|All|||||| +|Toyota|RAV4 Hybrid 2019-21|All|||||| ## Silver Cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| -|Audi|A3 2014-19|ACC + Lane Assist|||||| -|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| -|Audi|Q2 2018|ACC + Lane Assist|||||| -|Audi|Q3 2020-21|ACC + Lane Assist|||||| -|Audi|RS3 2018|ACC + Lane Assist|||||| -|Audi|S3 2015-17|ACC + Lane Assist|||||| -|Genesis|G70 2018|All|||||| -|Genesis|G80 2018|All|||||| -|Hyundai|Elantra 2021-22|SCC + LKAS|||||| -|Hyundai|Elantra Hybrid 2021-22|SCC + LKAS|||||| -|Hyundai|Ioniq Electric 2020|SCC + LKAS|||||| -|Hyundai|Ioniq Hybrid 2020-22|SCC + LFA|||||| -|Hyundai|Ioniq Plug-in Hybrid 2020-21|SCC + LKAS|||||| -|Hyundai|Kona 2020|SCC + LKAS|||||| -|Hyundai|Kona Electric 2018-21|SCC + LKAS|||||| -|Hyundai|Kona Hybrid 2020|SCC + LKAS|||||| -|Hyundai|Santa Fe 2021-22|All|||||| -|Hyundai|Santa Fe Hybrid 2022|All|||||| -|Hyundai|Santa Fe Plug-in Hybrid 2022|All|||||| -|Hyundai|Sonata 2018-19|SCC + LKAS|||||| -|Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| -|Kia|Ceed 2019|SCC + LKAS|||||| -|Kia|Forte 2018-21|SCC + LKAS|||||| -|Kia|K5 2021-22|SCC + LFA|||||| -|Kia|Niro Hybrid 2021-22|SCC + LKAS|||||| -|Kia|Optima 2019|SCC + LKAS|||||| -|Kia|Seltos 2021|SCC + LKAS|||||| -|Kia|Sorento 2018-19|SCC + LKAS|||||| -|Kia|Stinger 2018|SCC + LKAS|||||| -|Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| -|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| -|Lexus|NX 2018-19|All|[3](#footnotes)||||| -|Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| -|Lexus|RX 2016-18|All|[3](#footnotes)||||| -|Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| -|Mazda|CX-5 2022|All|||||| -|SEAT|Ateca 2018|Driver Assistance|||||| -|SEAT|Leon 2014-20|Driver Assistance|||||| -|Subaru|Crosstrek 2018-19|EyeSight|||||| -|Subaru|Forester 2019-21|EyeSight|||||| -|Subaru|Impreza 2017-19|EyeSight|||||| -|Å koda|Kamiq 2021[6](#footnotes)|Driver Assistance|||||| -|Å koda|Karoq 2019|Driver Assistance|||||| -|Å koda|Kodiaq 2018-19|Driver Assistance|||||| -|Å koda|Octavia 2015, 2018-19|Driver Assistance|||||| -|Å koda|Octavia RS 2016|Driver Assistance|||||| -|Å koda|Scala 2020|Driver Assistance|||||| -|Å koda|Superb 2015-18|Driver Assistance|||||| -|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| -|Toyota|C-HR 2017-21|All|||||| -|Toyota|C-HR Hybrid 2017-19|All|||||| -|Toyota|Camry 2018-20|All||[4](#footnotes)|||| -|Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| -|Toyota|Highlander 2017-19|All|[3](#footnotes)||||| -|Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| -|Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| -|Toyota|RAV4 Hybrid 2022|All|||||| -|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| -|Volkswagen|Arteon 2018, 2021[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Atlas 2018-19, 2022[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|e-Golf 2014, 2018-20|Driver Assistance|||||| -|Volkswagen|Golf 2015-20|Driver Assistance|||||| -|Volkswagen|Golf Alltrack 2017-18|Driver Assistance|||||| -|Volkswagen|Golf GTE 2016|Driver Assistance|||||| -|Volkswagen|Golf GTI 2018-21|Driver Assistance|||||| -|Volkswagen|Golf R 2016-19|Driver Assistance|||||| -|Volkswagen|Golf SportsVan 2016|Driver Assistance|||||| -|Volkswagen|Golf SportWagen 2015|Driver Assistance|||||| -|Volkswagen|Jetta 2018-21|Driver Assistance|||||| -|Volkswagen|Jetta GLI 2021|Driver Assistance|||||| -|Volkswagen|Passat 2016-18[7](#footnotes)|Driver Assistance|||||| -|Volkswagen|Polo 2020|Driver Assistance|||||| -|Volkswagen|T-Cross 2021[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|T-Roc 2021[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Taos 2022[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Tiguan 2019-22[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Touran 2017|Driver Assistance|||||| +|Audi|A3 2014-19|ACC + Lane Assist|||||| +|Audi|A3 Sportback e-tron 2017-18|ACC + Lane Assist|||||| +|Audi|Q2 2018|ACC + Lane Assist|||||| +|Audi|Q3 2020-21|ACC + Lane Assist|||||| +|Audi|RS3 2018|ACC + Lane Assist|||||| +|Audi|S3 2015-17|ACC + Lane Assist|||||| +|Genesis|G70 2018|All|||||| +|Genesis|G80 2018|All|||||| +|Hyundai|Elantra 2021-22|SCC + LKAS|||||| +|Hyundai|Elantra Hybrid 2021-22|SCC + LKAS|||||| +|Hyundai|Ioniq Electric 2020|SCC + LKAS|||||| +|Hyundai|Ioniq Hybrid 2020-22|SCC + LFA|||||| +|Hyundai|Ioniq Plug-in Hybrid 2020-21|SCC + LKAS|||||| +|Hyundai|Kona 2020|SCC + LKAS|||||| +|Hyundai|Kona Electric 2018-21|SCC + LKAS|||||| +|Hyundai|Kona Hybrid 2020|SCC + LKAS|||||| +|Hyundai|Santa Fe 2021-22|All|||||| +|Hyundai|Santa Fe Hybrid 2022|All|||||| +|Hyundai|Santa Fe Plug-in Hybrid 2022|All|||||| +|Hyundai|Sonata 2018-19|SCC + LKAS|||||| +|Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| +|Kia|Ceed 2019|SCC + LKAS|||||| +|Kia|Forte 2018-21|SCC + LKAS|||||| +|Kia|K5 2021-22|SCC + LFA|||||| +|Kia|Niro Hybrid 2021-22|SCC + LKAS|||||| +|Kia|Optima 2019|SCC + LKAS|||||| +|Kia|Seltos 2021|SCC + LKAS|||||| +|Kia|Sorento 2018-19|SCC + LKAS|||||| +|Kia|Stinger 2018|SCC + LKAS|||||| +|Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| +|Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| +|Lexus|NX 2018-19|All|[3](#footnotes)||||| +|Lexus|NX Hybrid 2018-19|All|[3](#footnotes)||||| +|Lexus|RX 2016-18|All|[3](#footnotes)||||| +|Lexus|RX Hybrid 2016-19|All|[3](#footnotes)||||| +|Mazda|CX-5 2022|All|||||| +|SEAT|Ateca 2018|Driver Assistance|||||| +|SEAT|Leon 2014-20|Driver Assistance|||||| +|Subaru|Crosstrek 2018-19|EyeSight|||||| +|Subaru|Forester 2019-21|EyeSight|||||| +|Subaru|Impreza 2017-19|EyeSight|||||| +|Å koda|Kamiq 2021[6](#footnotes)|Driver Assistance|||||| +|Å koda|Karoq 2019|Driver Assistance|||||| +|Å koda|Kodiaq 2018-19|Driver Assistance|||||| +|Å koda|Octavia 2015, 2018-19|Driver Assistance|||||| +|Å koda|Octavia RS 2016|Driver Assistance|||||| +|Å koda|Scala 2020|Driver Assistance|||||| +|Å koda|Superb 2015-18|Driver Assistance|||||| +|Toyota|Avalon 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|Avalon Hybrid 2019-21|TSS-P|[3](#footnotes)||||| +|Toyota|C-HR 2017-21|All|||||| +|Toyota|C-HR Hybrid 2017-19|All|||||| +|Toyota|Camry 2018-20|All||[4](#footnotes)|||| +|Toyota|Camry Hybrid 2018-20|All||[4](#footnotes)|||| +|Toyota|Highlander 2017-19|All|[3](#footnotes)||||| +|Toyota|Highlander Hybrid 2017-19|All|[3](#footnotes)||||| +|Toyota|RAV4 Hybrid 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|RAV4 Hybrid 2022|All|||||| +|Toyota|Sienna 2018-20|All|[3](#footnotes)||||| +|Volkswagen|Arteon 2018, 2021[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|Atlas 2018-19, 2022[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|e-Golf 2014, 2018-20|Driver Assistance|||||| +|Volkswagen|Golf 2015-20|Driver Assistance|||||| +|Volkswagen|Golf Alltrack 2017-18|Driver Assistance|||||| +|Volkswagen|Golf GTE 2016|Driver Assistance|||||| +|Volkswagen|Golf GTI 2018-21|Driver Assistance|||||| +|Volkswagen|Golf R 2016-19|Driver Assistance|||||| +|Volkswagen|Golf SportsVan 2016|Driver Assistance|||||| +|Volkswagen|Golf SportWagen 2015|Driver Assistance|||||| +|Volkswagen|Jetta 2018-21|Driver Assistance|||||| +|Volkswagen|Jetta GLI 2021|Driver Assistance|||||| +|Volkswagen|Passat 2016-18[7](#footnotes)|Driver Assistance|||||| +|Volkswagen|Polo 2020|Driver Assistance|||||| +|Volkswagen|T-Cross 2021[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|T-Roc 2021[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|Taos 2022[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|Tiguan 2019-22[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|Touran 2017|Driver Assistance|||||| ## Bronze Cars |Make|Model|Supported Package|openpilot ACC|Stop and Go|Steer to 0|Steering Torque|Actively Maintained| |---|---|---|:---:|:---:|:---:|:---:|:---:| -|Acura|ILX 2016-19|AcuraWatch Plus|||||| -|Acura|RDX 2016-18|AcuraWatch Plus|||||| -|Acura|RDX 2019-21|All|||||| -|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| -|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| -|Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica 2020|Adaptive Cruise|||||| -|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| -|Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| -|Genesis|G90 2018|All|||||| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| -|Honda|Accord 2018-21|All|||||| -|Honda|Accord Hybrid 2018-21|All|||||| -|Honda|Civic 2016-18|Honda Sensing|||||| -|Honda|Civic 2019-20|All|||[2](#footnotes)||| -|Honda|Civic Hatchback 2017-21|Honda Sensing|||||| -|Honda|CR-V 2015-16|Touring|||||| -|Honda|CR-V 2017-21|Honda Sensing|||||| -|Honda|CR-V Hybrid 2017-19|Honda Sensing|||||| -|Honda|e 2020|All|||||| -|Honda|Fit 2018-19|Honda Sensing|||||| -|Honda|Freed 2020|Honda Sensing|||||| -|Honda|HR-V 2019-20|Honda Sensing|||||| -|Honda|Insight 2019-21|All|||||| -|Honda|Inspire 2018|All|||||| -|Honda|Odyssey 2018-20|Honda Sensing|||||| -|Honda|Passport 2019-21|All|||||| -|Honda|Pilot 2016-21|Honda Sensing|||||| -|Honda|Ridgeline 2017-21|Honda Sensing|||||| -|Hyundai|Elantra 2017-19|SCC + LKAS|||||| -|Hyundai|Genesis 2015-16|SCC + LKAS|||||| -|Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| -|Hyundai|Ioniq Hybrid 2017-19|SCC + LKAS|||||| -|Hyundai|Ioniq Plug-in Hybrid 2019|SCC + LKAS|||||| -|Hyundai|Veloster 2019-20|SCC + LKAS|||||| -|Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| -|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| -|Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| -|Kia|Optima 2017|SCC + LKAS|||||| -|Lexus|IS 2017-19|All|||||| -|Lexus|RC 2020|All|||||| -|Mazda|CX-9 2021|All|||||| -|Nissan|Altima 2019-20|ProPILOT|||||| -|Nissan|Leaf 2018-22|ProPILOT|||||| -|Nissan|Rogue 2018-20|ProPILOT|||||| -|Nissan|X-Trail 2017|ProPILOT|||||| -|Subaru|Ascent 2019-20|EyeSight|||||| -|Subaru|Crosstrek 2020-21|EyeSight|||||| -|Subaru|Impreza 2020-21|EyeSight|||||| -|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| -|Toyota|Corolla 2017-19|All|[3](#footnotes)||||| -|Toyota|Prius 2016-20|TSS-P|[3](#footnotes)|||[5](#footnotes)|| -|Toyota|Prius Prime 2017-20|All|[3](#footnotes)|||[5](#footnotes)|| -|Toyota|Prius v 2017|TSS-P|[3](#footnotes)|||[5](#footnotes)|| -|Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| -|Volkswagen|California 2021[8](#footnotes)|Driver Assistance|||||| -|Volkswagen|Caravelle 2020[8](#footnotes)|Driver Assistance|||||| +|Acura|ILX 2016-19|AcuraWatch Plus|||||| +|Acura|RDX 2016-18|AcuraWatch Plus|||||| +|Acura|RDX 2019-21|All|||||| +|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| +|Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| +|Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| +|Chrysler|Pacifica 2020|Adaptive Cruise|||||| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| +|Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| +|Genesis|G90 2018|All|||||| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| +|Honda|Accord 2018-21|All|||||| +|Honda|Accord Hybrid 2018-21|All|||||| +|Honda|Civic 2016-18|Honda Sensing|||||| +|Honda|Civic 2019-20|All|||[2](#footnotes)||| +|Honda|Civic Hatchback 2017-21|Honda Sensing|||||| +|Honda|CR-V 2015-16|Touring|||||| +|Honda|CR-V 2017-21|Honda Sensing|||||| +|Honda|CR-V Hybrid 2017-19|Honda Sensing|||||| +|Honda|e 2020|All|||||| +|Honda|Fit 2018-19|Honda Sensing|||||| +|Honda|Freed 2020|Honda Sensing|||||| +|Honda|HR-V 2019-20|Honda Sensing|||||| +|Honda|Insight 2019-21|All|||||| +|Honda|Inspire 2018|All|||||| +|Honda|Odyssey 2018-20|Honda Sensing|||||| +|Honda|Passport 2019-21|All|||||| +|Honda|Pilot 2016-21|Honda Sensing|||||| +|Honda|Ridgeline 2017-21|Honda Sensing|||||| +|Hyundai|Elantra 2017-19|SCC + LKAS|||||| +|Hyundai|Genesis 2015-16|SCC + LKAS|||||| +|Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| +|Hyundai|Ioniq Hybrid 2017-19|SCC + LKAS|||||| +|Hyundai|Ioniq Plug-in Hybrid 2019|SCC + LKAS|||||| +|Hyundai|Veloster 2019-20|SCC + LKAS|||||| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise|||||| +|Jeep|Grand Cherokee 2019-20|Adaptive Cruise|||||| +|Kia|Niro Plug-in Hybrid 2019|SCC + LKAS|||||| +|Kia|Optima 2017|SCC + LKAS|||||| +|Lexus|IS 2017-19|All|||||| +|Lexus|RC 2020|All|||||| +|Mazda|CX-9 2021|All|||||| +|Nissan|Altima 2019-20|ProPILOT|||||| +|Nissan|Leaf 2018-22|ProPILOT|||||| +|Nissan|Rogue 2018-20|ProPILOT|||||| +|Nissan|X-Trail 2017|ProPILOT|||||| +|Subaru|Ascent 2019-20|EyeSight|||||| +|Subaru|Crosstrek 2020-21|EyeSight|||||| +|Subaru|Impreza 2020-21|EyeSight|||||| +|Toyota|Avalon 2016-18|TSS-P|[3](#footnotes)||||| +|Toyota|Corolla 2017-19|All|[3](#footnotes)||||| +|Toyota|Prius 2016-20|TSS-P|[3](#footnotes)|||[5](#footnotes)|| +|Toyota|Prius Prime 2017-20|All|[3](#footnotes)|||[5](#footnotes)|| +|Toyota|Prius v 2017|TSS-P|[3](#footnotes)|||[5](#footnotes)|| +|Toyota|RAV4 2016-18|TSS-P|[3](#footnotes)||||| +|Volkswagen|California 2021[8](#footnotes)|Driver Assistance|||||| +|Volkswagen|Caravelle 2020[8](#footnotes)|Driver Assistance|||||| diff --git a/selfdrive/car/CARS_template.md b/selfdrive/car/CARS_template.md index 2165bf48bb..cd9b7bc6ee 100644 --- a/selfdrive/car/CARS_template.md +++ b/selfdrive/car/CARS_template.md @@ -1,5 +1,5 @@ {% set footnote_tag = '[{}](#footnotes)' -%} -{% set star_icon = '' -%} +{% set star_icon = '' -%} # Supported Cars From f9af3ddf4c819127119943cafec6e46fe75a49af Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Mon, 9 May 2022 22:00:31 -0700 Subject: [PATCH 074/391] CARS.md: update Honda Ridgeline supported years (#24484) * update supported ridgeline years * update supported ridgeline years --- docs/CARS.md | 2 +- selfdrive/car/honda/values.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index 02dfdedba1..d41a112468 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -184,7 +184,7 @@ How We Rate The Cars |Honda|Odyssey 2018-20|Honda Sensing|||||| |Honda|Passport 2019-21|All|||||| |Honda|Pilot 2016-21|Honda Sensing|||||| -|Honda|Ridgeline 2017-21|Honda Sensing|||||| +|Honda|Ridgeline 2017-22|Honda Sensing|||||| |Hyundai|Elantra 2017-19|SCC + LKAS|||||| |Hyundai|Genesis 2015-16|SCC + LKAS|||||| |Hyundai|Ioniq Electric 2019|SCC + LKAS|||||| diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index fa369d1c9a..64c7dd8420 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -130,7 +130,7 @@ CAR_INFO: Dict[str, Union[HondaCarInfo, List[HondaCarInfo]]] = { CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21"), CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All"), - CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-21"), + CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22"), CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS), } From 01ab99d416ffa6fb5f96ebd2091be94a3dc6c6bf Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 10 May 2022 14:21:22 -0700 Subject: [PATCH 075/391] simplify and fix clamp (#24479) Co-authored-by: Comma Device --- selfdrive/camerad/cameras/real_debayer.cl | 64 ++++++++++------------- 1 file changed, 27 insertions(+), 37 deletions(-) diff --git a/selfdrive/camerad/cameras/real_debayer.cl b/selfdrive/camerad/cameras/real_debayer.cl index dee7f241a4..a1a7fd6279 100644 --- a/selfdrive/camerad/cameras/real_debayer.cl +++ b/selfdrive/camerad/cameras/real_debayer.cl @@ -13,30 +13,33 @@ const __constant half3 color_correction_2 = (half3)(-0.25277411, -0.05627105, 1. // tone mapping params const half gamma_k = 0.75; const half gamma_b = 0.125; -const half mp_default = 0.01; // ideally midpoint should be adaptive +const half mp = 0.01; // ideally midpoint should be adaptive +const half rk = 9 - 100*mp; -half gamma_apply(half x, half mp) { +inline half3 gamma_apply(half3 x) { // poly approximation for s curve - half rk = 9 - 100*mp; - if (x > mp) { - return (rk * (x-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(x-mp))) + gamma_k*mp + gamma_b; - } else if (x < mp) { - return (rk * (x-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(x-mp))) + gamma_k*mp + gamma_b; - } else { - return x; - } + return (x > mp) ? + ((rk * (x-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(x-mp))) + gamma_k*mp + gamma_b) : + ((rk * (x-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(x-mp))) + gamma_k*mp + gamma_b); } -half3 color_correct(half3 rgb) { - half3 ret = (half3)(0.0, 0.0, 0.0); - ret += (half)rgb.x * color_correction_0; +inline half3 color_correct(half3 rgb) { + half3 ret = (half)rgb.x * color_correction_0; ret += (half)rgb.y * color_correction_1; ret += (half)rgb.z * color_correction_2; - ret.x = gamma_apply(ret.x, mp_default); - ret.y = gamma_apply(ret.y, mp_default); - ret.z = gamma_apply(ret.z, mp_default); - ret = clamp(0.0, 255.0, ret*255.0); - return ret; + return gamma_apply(ret); +} + +inline half get_vignetting_s(float r) { + if (r < 62500) { + return (half)(1.0f + 0.0000008f*r); + } else if (r < 490000) { + return (half)(0.9625f + 0.0000014f*r); + } else if (r < 1102500) { + return (half)(1.26434f + 0.0000000000016f*r*r); + } else { + return (half)(0.53503625f + 0.0000000000022f*r*r); + } } inline half val_from_10(const uchar * source, int gx, int gy, half black_level) { @@ -55,21 +58,10 @@ inline half val_from_10(const uchar * source, int gx, int gy, half black_level) if (CAM_NUM == 1) { // fcamera gx = (gx - RGB_WIDTH/2); gy = (gy - RGB_HEIGHT/2); - float r = gx*gx + gy*gy; - half s; - if (r < 62500) { - s = (half)(1.0f + 0.0000008f*r); - } else if (r < 490000) { - s = (half)(0.9625f + 0.0000014f*r); - } else if (r < 1102500) { - s = (half)(1.26434f + 0.0000000000016f*r*r); - } else { - s = (half)(0.53503625f + 0.0000000000022f*r*r); - } - pv = s * pv; + pv *= get_vignetting_s(gx*gx + gy*gy); } - pv = clamp((half)0.0, (half)1.0, pv); + pv = clamp(pv, (half)0.0, (half)1.0); return pv; } @@ -197,10 +189,8 @@ __kernel void debayer10(const __global uchar * in, } } - rgb = clamp(0.0, 1.0, rgb); - rgb = color_correct(rgb); - - out[out_idx + 0] = (uchar)(rgb.z); - out[out_idx + 1] = (uchar)(rgb.y); - out[out_idx + 2] = (uchar)(rgb.x); + uchar3 rgbc = convert_uchar3_sat(color_correct(clamp(rgb, (half)0.0, (half)1.0)) * 255.0); + out[out_idx + 0] = rgbc.z; + out[out_idx + 1] = rgbc.y; + out[out_idx + 2] = rgbc.x; } From 2008db47c208f6f0fd661cc45f215bb80aef38d0 Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 10 May 2022 15:20:51 -0700 Subject: [PATCH 076/391] encoderd: make work on PC (#24483) * don't use the codec in video_writer * this produces broken videos for some reason * bugfix * refactor on the class * works on device * fix codec * no codec enum * fix pc * move into dirs * these includes also * rename it ffmpegencoder * add avcodec_close Co-authored-by: Comma Device --- cereal | 2 +- release/files_common | 15 +-- selfdrive/loggerd/SConscript | 9 +- selfdrive/loggerd/encoder.h | 13 --- selfdrive/loggerd/encoder/encoder.cc | 79 ++++++++++++++++ selfdrive/loggerd/encoder/encoder.h | 60 ++++++++++++ .../ffmpeg_encoder.cc} | 58 ++++++++---- selfdrive/loggerd/encoder/ffmpeg_encoder.h | 38 ++++++++ .../loggerd/{ => encoder}/v4l_encoder.cc | 94 ++----------------- selfdrive/loggerd/{ => encoder}/v4l_encoder.h | 26 ++--- .../loggerd/{ => encoder}/video_writer.cc | 27 +++--- .../loggerd/{ => encoder}/video_writer.h | 6 +- selfdrive/loggerd/encoderd.cc | 6 +- selfdrive/loggerd/loggerd.cc | 8 +- selfdrive/loggerd/loggerd.h | 8 +- selfdrive/loggerd/raw_logger.h | 41 -------- selfdrive/loggerd/remote_encoder.cc | 2 +- selfdrive/loggerd/remote_encoder.h | 3 +- tools/camerastream/compressed_vipc.py | 2 +- 19 files changed, 279 insertions(+), 218 deletions(-) delete mode 100644 selfdrive/loggerd/encoder.h create mode 100644 selfdrive/loggerd/encoder/encoder.cc create mode 100644 selfdrive/loggerd/encoder/encoder.h rename selfdrive/loggerd/{raw_logger.cc => encoder/ffmpeg_encoder.cc} (58%) create mode 100644 selfdrive/loggerd/encoder/ffmpeg_encoder.h rename selfdrive/loggerd/{ => encoder}/v4l_encoder.cc (75%) rename selfdrive/loggerd/{ => encoder}/v4l_encoder.h (52%) rename selfdrive/loggerd/{ => encoder}/video_writer.cc (83%) rename selfdrive/loggerd/{ => encoder}/video_writer.h (80%) delete mode 100644 selfdrive/loggerd/raw_logger.h diff --git a/cereal b/cereal index c7d3a0acba..67e5c5ca37 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit c7d3a0acbae267ef93d30044e1941e060dac9e48 +Subproject commit 67e5c5ca378fcf6db53e968e5ad9e4a98d32ed0f diff --git a/release/files_common b/release/files_common index c44f10229e..46f555fe0b 100644 --- a/release/files_common +++ b/release/files_common @@ -298,11 +298,12 @@ selfdrive/proclogd/proclog.cc selfdrive/proclogd/proclog.h selfdrive/loggerd/SConscript -selfdrive/loggerd/encoder.h -selfdrive/loggerd/v4l_encoder.cc -selfdrive/loggerd/v4l_encoder.h -selfdrive/loggerd/video_writer.cc -selfdrive/loggerd/video_writer.h +selfdrive/loggerd/encoder/encoder.cc +selfdrive/loggerd/encoder/encoder.h +selfdrive/loggerd/encoder/v4l_encoder.cc +selfdrive/loggerd/encoder/v4l_encoder.h +selfdrive/loggerd/encoder/video_writer.cc +selfdrive/loggerd/encoder/video_writer.h selfdrive/loggerd/remote_encoder.cc selfdrive/loggerd/remote_encoder.h selfdrive/loggerd/logger.cc @@ -312,8 +313,8 @@ selfdrive/loggerd/loggerd.h selfdrive/loggerd/encoderd.cc selfdrive/loggerd/main.cc selfdrive/loggerd/bootlog.cc -selfdrive/loggerd/raw_logger.cc -selfdrive/loggerd/raw_logger.h +selfdrive/loggerd/encoder/ffmpeg_encoder.cc +selfdrive/loggerd/encoder/ffmpeg_encoder.h selfdrive/loggerd/__init__.py selfdrive/loggerd/config.py diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 7403dafb6d..81eca19a47 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -5,11 +5,11 @@ libs = [common, cereal, messaging, visionipc, 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'OpenCL', 'pthread'] -src = ['logger.cc', 'loggerd.cc', 'video_writer.cc', 'remote_encoder.cc'] +src = ['logger.cc', 'loggerd.cc', 'encoder/video_writer.cc', 'remote_encoder.cc', 'encoder/encoder.cc'] if arch == "larch64": - src += ['v4l_encoder.cc'] + src += ['encoder/v4l_encoder.cc'] else: - src += ['raw_logger.cc'] + src += ['encoder/ffmpeg_encoder.cc'] if arch == "Darwin": # fix OpenCL @@ -20,8 +20,7 @@ logger_lib = env.Library('logger', src) libs.insert(0, logger_lib) env.Program('loggerd', ['main.cc'], LIBS=libs) -if arch == "larch64": - env.Program('encoderd', ['encoderd.cc'], LIBS=libs) +env.Program('encoderd', ['encoderd.cc'], LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): diff --git a/selfdrive/loggerd/encoder.h b/selfdrive/loggerd/encoder.h deleted file mode 100644 index 0a5afa007c..0000000000 --- a/selfdrive/loggerd/encoder.h +++ /dev/null @@ -1,13 +0,0 @@ -#pragma once - -#include -#include "cereal/visionipc/visionipc.h" - -class VideoEncoder { -public: - virtual ~VideoEncoder() {} - virtual int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, VisionIpcBufExtra *extra) = 0; - virtual void encoder_open(const char* path) = 0; - virtual void encoder_close() = 0; -}; diff --git a/selfdrive/loggerd/encoder/encoder.cc b/selfdrive/loggerd/encoder/encoder.cc new file mode 100644 index 0000000000..84f26d9787 --- /dev/null +++ b/selfdrive/loggerd/encoder/encoder.cc @@ -0,0 +1,79 @@ +#include +#include "selfdrive/loggerd/encoder/encoder.h" + +VideoEncoder::~VideoEncoder() {} + +void VideoEncoder::publisher_init() { + // publish + service_name = this->type == DriverCam ? "driverEncodeData" : + (this->type == WideRoadCam ? "wideRoadEncodeData" : + (this->in_width == this->out_width ? "roadEncodeData" : "qRoadEncodeData")); + pm.reset(new PubMaster({service_name})); +} + +void VideoEncoder::publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, + unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat) { + // broadcast packet + MessageBuilder msg; + auto event = msg.initEvent(true); + auto edat = (e->type == DriverCam) ? event.initDriverEncodeData() : + ((e->type == WideRoadCam) ? event.initWideRoadEncodeData() : + (e->in_width == e->out_width ? event.initRoadEncodeData() : event.initQRoadEncodeData())); + auto edata = edat.initIdx(); + edata.setFrameId(extra.frame_id); + edata.setTimestampSof(extra.timestamp_sof); + edata.setTimestampEof(extra.timestamp_eof); + edata.setType(e->codec); + edata.setEncodeId(idx); + edata.setSegmentNum(segment_num); + edata.setSegmentId(idx); + edata.setFlags(flags); + edata.setLen(dat.size()); + edat.setData(dat); + if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); + + auto words = new kj::Array(capnp::messageToFlatArray(msg)); + auto bytes = words->asBytes(); + e->pm->send(e->service_name, bytes.begin(), bytes.size()); + if (e->write) { + e->to_write.push(words); + } else { + delete words; + } +} + +// TODO: writing should be moved to loggerd +void VideoEncoder::write_handler(VideoEncoder *e, const char *path) { + VideoWriter writer(path, e->filename, e->codec != cereal::EncodeIndex::Type::FULL_H_E_V_C, e->out_width, e->out_height, e->fps, e->codec); + + bool first = true; + kj::Array* out_buf; + while ((out_buf = e->to_write.pop())) { + capnp::FlatArrayMessageReader cmsg(*out_buf); + cereal::Event::Reader event = cmsg.getRoot(); + + auto edata = (e->type == DriverCam) ? event.getDriverEncodeData() : + ((e->type == WideRoadCam) ? event.getWideRoadEncodeData() : + (e->in_width == e->out_width ? event.getRoadEncodeData() : event.getQRoadEncodeData())); + auto idx = edata.getIdx(); + auto flags = idx.getFlags(); + + if (first) { + assert(flags & V4L2_BUF_FLAG_KEYFRAME); + auto header = edata.getHeader(); + writer.write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); + first = false; + } + + // dangerous cast from const, but should be fine + auto data = edata.getData(); + if (data.size() > 0) { + writer.write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); + } + + // free the data + delete out_buf; + } + + // VideoWriter is freed on out of scope +} diff --git a/selfdrive/loggerd/encoder/encoder.h b/selfdrive/loggerd/encoder/encoder.h new file mode 100644 index 0000000000..abdcc9c4bf --- /dev/null +++ b/selfdrive/loggerd/encoder/encoder.h @@ -0,0 +1,60 @@ +#pragma once + +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "cereal/visionipc/visionipc.h" +#include "selfdrive/common/queue.h" +#include "selfdrive/loggerd/encoder/video_writer.h" +#include "selfdrive/camerad/cameras/camera_common.h" + +#define V4L2_BUF_FLAG_KEYFRAME 8 + +class VideoEncoder { +public: + VideoEncoder(const char* filename, CameraType type, int in_width, int in_height, int fps, + int bitrate, cereal::EncodeIndex::Type codec, int out_width, int out_height, bool write) + : filename(filename), type(type), in_width(in_width), in_height(in_height), fps(fps), + bitrate(bitrate), codec(codec), out_width(out_width), out_height(out_height), write(write) { } + virtual ~VideoEncoder(); + virtual int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width, int in_height, VisionIpcBufExtra *extra) = 0; + virtual void encoder_open(const char* path) = 0; + virtual void encoder_close() = 0; + + void publisher_init(); + static void publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat); + + void writer_open(const char* path) { + if (this->write) write_handler_thread = std::thread(VideoEncoder::write_handler, this, path); + } + + void writer_close() { + if (this->write) { + to_write.push(NULL); + write_handler_thread.join(); + } + assert(to_write.empty()); + } + +protected: + bool write; + const char* filename; + int in_width, in_height; + int out_width, out_height, fps; + int bitrate; + cereal::EncodeIndex::Type codec; + CameraType type; + +private: + // publishing + std::unique_ptr pm; + const char *service_name; + + // writing support + static void write_handler(VideoEncoder *e, const char *path); + std::thread write_handler_thread; + SafeQueue* > to_write; +}; diff --git a/selfdrive/loggerd/raw_logger.cc b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc similarity index 58% rename from selfdrive/loggerd/raw_logger.cc rename to selfdrive/loggerd/encoder/ffmpeg_encoder.cc index 72c8d0d93e..139ffe3f24 100644 --- a/selfdrive/loggerd/raw_logger.cc +++ b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc @@ -1,6 +1,6 @@ #pragma clang diagnostic ignored "-Wdeprecated-declarations" -#include "selfdrive/loggerd/raw_logger.h" +#include "selfdrive/loggerd/encoder/ffmpeg_encoder.h" #include #include @@ -22,10 +22,9 @@ extern "C" { #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" -RawLogger::RawLogger(const char* filename, CameraType type, int in_width, int in_height, int fps, - int bitrate, bool h265, int out_width, int out_height, bool write) - : in_width_(in_width), in_height_(in_height), filename(filename), fps(fps) { - // TODO: respect write arg +const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0; + +void FfmpegEncoder::encoder_init() { frame = av_frame_alloc(); assert(frame); frame->format = AV_PIX_FMT_YUV420P; @@ -38,30 +37,43 @@ RawLogger::RawLogger(const char* filename, CameraType type, int in_width, int in if (in_width != out_width || in_height != out_height) { downscale_buf.resize(out_width * out_height * 3 / 2); } + + publisher_init(); } -RawLogger::~RawLogger() { +FfmpegEncoder::~FfmpegEncoder() { encoder_close(); av_frame_free(&frame); } -void RawLogger::encoder_open(const char* path) { - writer = new VideoWriter(path, this->filename, true, frame->width, frame->height, this->fps, false, true); - // write the header - writer->write(NULL, 0, 0, true, false); +void FfmpegEncoder::encoder_open(const char* path) { + AVCodec *codec = avcodec_find_encoder(AV_CODEC_ID_FFVHUFF); + + this->codec_ctx = avcodec_alloc_context3(codec); + assert(this->codec_ctx); + this->codec_ctx->width = frame->width; + this->codec_ctx->height = frame->height; + this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P; + this->codec_ctx->time_base = (AVRational){ 1, fps }; + int err = avcodec_open2(this->codec_ctx, codec, NULL); + assert(err >= 0); + + writer_open(path); is_open = true; + segment_num++; + counter = 0; } -void RawLogger::encoder_close() { +void FfmpegEncoder::encoder_close() { if (!is_open) return; - delete writer; + writer_close(); is_open = false; } -int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, VisionIpcBufExtra *extra) { - assert(in_width == this->in_width_); - assert(in_height == this->in_height_); +int FfmpegEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width_, int in_height_, VisionIpcBufExtra *extra) { + assert(in_width_ == this->in_width); + assert(in_height_ == this->in_height); if (downscale_buf.size() > 0) { uint8_t *out_y = downscale_buf.data(); @@ -88,7 +100,7 @@ int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const ui int ret = counter; - int err = avcodec_send_frame(writer->codec_ctx, frame); + int err = avcodec_send_frame(this->codec_ctx, frame); if (err < 0) { LOGE("avcodec_send_frame error %d", err); ret = -1; @@ -99,7 +111,7 @@ int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const ui pkt.data = NULL; pkt.size = 0; while (ret >= 0) { - err = avcodec_receive_packet(writer->codec_ctx, &pkt); + err = avcodec_receive_packet(this->codec_ctx, &pkt); if (err == AVERROR_EOF) { break; } else if (err == AVERROR(EAGAIN)) { @@ -112,7 +124,15 @@ int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const ui break; } - writer->write(pkt.data, pkt.size, pkt.pts, false, pkt.flags & AV_PKT_FLAG_KEY); + if (env_debug_encoder) { + printf("%20s got %8d bytes flags %8x idx %4d id %8d\n", this->filename, pkt.size, pkt.flags, counter, extra->frame_id); + } + + publisher_publish(this, segment_num, counter, *extra, + (pkt.flags & AV_PKT_FLAG_KEY) ? V4L2_BUF_FLAG_KEYFRAME : 0, + kj::arrayPtr(pkt.data, (size_t)0), // TODO: get the header + kj::arrayPtr(pkt.data, pkt.size)); + counter++; } av_packet_unref(&pkt); diff --git a/selfdrive/loggerd/encoder/ffmpeg_encoder.h b/selfdrive/loggerd/encoder/ffmpeg_encoder.h new file mode 100644 index 0000000000..5f90e198fc --- /dev/null +++ b/selfdrive/loggerd/encoder/ffmpeg_encoder.h @@ -0,0 +1,38 @@ +#pragma once + +#include +#include +#include +#include + +extern "C" { +#include +#include +#include +} + +#include "selfdrive/loggerd/encoder/encoder.h" +#include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/encoder/video_writer.h" + +class FfmpegEncoder : public VideoEncoder { + public: + FfmpegEncoder(const char* filename, CameraType type, int in_width, int in_height, int fps, + int bitrate, cereal::EncodeIndex::Type codec, int out_width, int out_height, bool write) : + VideoEncoder(filename, type, in_width, in_height, fps, bitrate, cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS, out_width, out_height, write) { encoder_init(); } + ~FfmpegEncoder(); + void encoder_init(); + int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width_, int in_height_, VisionIpcBufExtra *extra); + void encoder_open(const char* path); + void encoder_close(); + +private: + int segment_num = -1; + int counter = 0; + bool is_open = false; + + AVCodecContext *codec_ctx; + AVFrame *frame = NULL; + std::vector downscale_buf; +}; diff --git a/selfdrive/loggerd/v4l_encoder.cc b/selfdrive/loggerd/encoder/v4l_encoder.cc similarity index 75% rename from selfdrive/loggerd/v4l_encoder.cc rename to selfdrive/loggerd/encoder/v4l_encoder.cc index 99653758a0..f5608a067e 100644 --- a/selfdrive/loggerd/v4l_encoder.cc +++ b/selfdrive/loggerd/encoder/v4l_encoder.cc @@ -2,7 +2,7 @@ #include #include -#include "selfdrive/loggerd/v4l_encoder.h" +#include "selfdrive/loggerd/encoder/v4l_encoder.h" #include "selfdrive/common/util.h" #include "selfdrive/common/timing.h" @@ -67,42 +67,6 @@ static void request_buffers(int fd, v4l2_buf_type buf_type, unsigned int count) checked_ioctl(fd, VIDIOC_REQBUFS, &reqbuf); } -// TODO: writing should be moved to loggerd -void V4LEncoder::write_handler(V4LEncoder *e, const char *path) { - VideoWriter writer(path, e->filename, !e->h265, e->width, e->height, e->fps, e->h265, false); - - bool first = true; - kj::Array* out_buf; - while ((out_buf = e->to_write.pop())) { - capnp::FlatArrayMessageReader cmsg(*out_buf); - cereal::Event::Reader event = cmsg.getRoot(); - - auto edata = (e->type == DriverCam) ? event.getDriverEncodeData() : - ((e->type == WideRoadCam) ? event.getWideRoadEncodeData() : - (e->h265 ? event.getRoadEncodeData() : event.getQRoadEncodeData())); - auto idx = edata.getIdx(); - auto flags = idx.getFlags(); - - if (first) { - assert(flags & V4L2_BUF_FLAG_KEYFRAME); - auto header = edata.getHeader(); - writer.write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); - first = false; - } - - // dangerous cast from const, but should be fine - auto data = edata.getData(); - if (data.size() > 0) { - writer.write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); - } - - // free the data - delete out_buf; - } - - // VideoWriter is freed on out of scope -} - void V4LEncoder::dequeue_handler(V4LEncoder *e) { std::string dequeue_thread_name = "dq-"+std::string(e->filename); util::set_thread_name(dequeue_thread_name.c_str()); @@ -138,7 +102,6 @@ void V4LEncoder::dequeue_handler(V4LEncoder *e) { // eof packet, we exit if (flags & V4L2_QCOM_BUF_FLAG_EOS) { - if (e->write) e->to_write.push(NULL); exit = true; } else if (flags & V4L2_QCOM_BUF_FLAG_CODECCONFIG) { // save header @@ -146,37 +109,9 @@ void V4LEncoder::dequeue_handler(V4LEncoder *e) { } else { VisionIpcBufExtra extra = e->extras.pop(); assert(extra.timestamp_eof/1000 == ts); // stay in sync - frame_id = extra.frame_id; ++idx; - - // broadcast packet - MessageBuilder msg; - auto event = msg.initEvent(true); - auto edat = (e->type == DriverCam) ? event.initDriverEncodeData() : - ((e->type == WideRoadCam) ? event.initWideRoadEncodeData() : - (e->h265 ? event.initRoadEncodeData() : event.initQRoadEncodeData())); - auto edata = edat.initIdx(); - edata.setFrameId(extra.frame_id); - edata.setTimestampSof(extra.timestamp_sof); - edata.setTimestampEof(extra.timestamp_eof); - edata.setType(e->h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264); - edata.setEncodeId(idx); - edata.setSegmentNum(e->segment_num); - edata.setSegmentId(idx); - edata.setFlags(flags); - edata.setLen(bytesused); - edat.setData(kj::arrayPtr(buf, bytesused)); - if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); - - auto words = new kj::Array(capnp::messageToFlatArray(msg)); - auto bytes = words->asBytes(); - e->pm->send(e->service_name, bytes.begin(), bytes.size()); - if (e->write) { - e->to_write.push(words); - } else { - delete words; - } + e->publisher_publish(e, e->segment_num, idx, extra, flags, header, kj::arrayPtr(buf, bytesused)); } if (env_debug_encoder) { @@ -196,12 +131,7 @@ void V4LEncoder::dequeue_handler(V4LEncoder *e) { } } -V4LEncoder::V4LEncoder( - const char* filename, CameraType type, int in_width, int in_height, - int fps, int bitrate, bool h265, int out_width, int out_height, bool write) - : type(type), in_width_(in_width), in_height_(in_height), - filename(filename), h265(h265), - width(out_width), height(out_height), fps(fps), write(write) { +void V4LEncoder::encoder_init() { fd = open("/dev/v4l/by-path/platform-aa00000.qcom_vidc-video-index1", O_RDWR|O_NONBLOCK); assert(fd >= 0); @@ -218,7 +148,7 @@ V4LEncoder::V4LEncoder( // downscales are free with v4l .width = (unsigned int)out_width, .height = (unsigned int)out_height, - .pixelformat = h265 ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, + .pixelformat = (codec == cereal::EncodeIndex::Type::FULL_H_E_V_C) ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, .field = V4L2_FIELD_ANY, .colorspace = V4L2_COLORSPACE_DEFAULT, } @@ -272,7 +202,7 @@ V4LEncoder::V4LEncoder( } } - if (h265) { + if (codec == cereal::EncodeIndex::Type::FULL_H_E_V_C) { struct v4l2_control ctrls[] = { { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN}, { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5}, @@ -321,23 +251,18 @@ V4LEncoder::V4LEncoder( free_buf_in.push(i); } - // publish - service_name = this->type == DriverCam ? "driverEncodeData" : - (this->type == WideRoadCam ? "wideRoadEncodeData" : - (this->h265 ? "roadEncodeData" : "qRoadEncodeData")); - pm.reset(new PubMaster({service_name})); + publisher_init(); } - void V4LEncoder::encoder_open(const char* path) { dequeue_handler_thread = std::thread(V4LEncoder::dequeue_handler, this); - if (this->write) write_handler_thread = std::thread(V4LEncoder::write_handler, this, path); + writer_open(path); this->is_open = true; this->counter = 0; } int V4LEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, VisionIpcBufExtra *extra) { + int in_width_, int in_height_, VisionIpcBufExtra *extra) { assert(in_width == in_width_); assert(in_height == in_height_); assert(is_open); @@ -383,8 +308,7 @@ void V4LEncoder::encoder_close() { // join waits for V4L2_QCOM_BUF_FLAG_EOS dequeue_handler_thread.join(); assert(extras.empty()); - if (this->write) write_handler_thread.join(); - assert(to_write.empty()); + writer_close(); } this->is_open = false; } diff --git a/selfdrive/loggerd/v4l_encoder.h b/selfdrive/loggerd/encoder/v4l_encoder.h similarity index 52% rename from selfdrive/loggerd/v4l_encoder.h rename to selfdrive/loggerd/encoder/v4l_encoder.h index 43b70baebd..13ebab20da 100644 --- a/selfdrive/loggerd/v4l_encoder.h +++ b/selfdrive/loggerd/encoder/v4l_encoder.h @@ -1,17 +1,19 @@ #pragma once #include "selfdrive/common/queue.h" -#include "selfdrive/loggerd/encoder.h" -#include "selfdrive/loggerd/loggerd.h" -#include "selfdrive/loggerd/video_writer.h" +#include "selfdrive/loggerd/encoder/encoder.h" +#include "selfdrive/loggerd/encoder/video_writer.h" #define BUF_IN_COUNT 7 #define BUF_OUT_COUNT 6 class V4LEncoder : public VideoEncoder { public: - V4LEncoder(const char* filename, CameraType type, int width, int height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write = true); + V4LEncoder(const char* filename, CameraType type, int in_width, int in_height, int fps, + int bitrate, cereal::EncodeIndex::Type codec, int out_width, int out_height, bool write) : + VideoEncoder(filename, type, in_width, in_height, fps, bitrate, codec, out_width, out_height, write) { encoder_init(); } ~V4LEncoder(); + void encoder_init(); int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, int in_width, int in_height, VisionIpcBufExtra *extra); void encoder_open(const char* path); @@ -19,16 +21,11 @@ public: private: int fd; - const char* filename; - CameraType type; - unsigned int in_width_, in_height_; - bool h265; bool is_open = false; int segment_num = -1; int counter = 0; - std::unique_ptr pm; - const char *service_name; + SafeQueue extras; static void dequeue_handler(V4LEncoder *e); std::thread dequeue_handler_thread; @@ -36,13 +33,4 @@ private: VisionBuf buf_in[BUF_IN_COUNT]; VisionBuf buf_out[BUF_OUT_COUNT]; SafeQueue free_buf_in; - - SafeQueue extras; - - // writing support - int width, height, fps; - bool write; - static void write_handler(V4LEncoder *e, const char *path); - std::thread write_handler_thread; - SafeQueue* > to_write; }; diff --git a/selfdrive/loggerd/video_writer.cc b/selfdrive/loggerd/encoder/video_writer.cc similarity index 83% rename from selfdrive/loggerd/video_writer.cc rename to selfdrive/loggerd/encoder/video_writer.cc index 51e606dc5c..c02592583a 100644 --- a/selfdrive/loggerd/video_writer.cc +++ b/selfdrive/loggerd/encoder/video_writer.cc @@ -3,12 +3,13 @@ #include #include -#include "selfdrive/loggerd/video_writer.h" +#include "selfdrive/loggerd/encoder/video_writer.h" #include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" -VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, bool h265, bool raw) - : remuxing(remuxing), raw(raw) { +VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, cereal::EncodeIndex::Type codec) + : remuxing(remuxing) { + raw = codec == cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS; vid_path = util::string_format("%s/%s", path, filename); lock_path = util::string_format("%s/%s.lock", path, filename); @@ -24,25 +25,25 @@ VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, // set codec correctly. needed? av_register_all(); - AVCodec *codec = NULL; - assert(!h265); - codec = avcodec_find_encoder(raw ? AV_CODEC_ID_FFVHUFF : AV_CODEC_ID_H264); - assert(codec); + AVCodec *avcodec = NULL; + assert(codec != cereal::EncodeIndex::Type::FULL_H_E_V_C); + avcodec = avcodec_find_encoder(raw ? AV_CODEC_ID_FFVHUFF : AV_CODEC_ID_H264); + assert(avcodec); - this->codec_ctx = avcodec_alloc_context3(codec); + this->codec_ctx = avcodec_alloc_context3(avcodec); assert(this->codec_ctx); this->codec_ctx->width = width; this->codec_ctx->height = height; this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P; this->codec_ctx->time_base = (AVRational){ 1, fps }; - if (raw) { - // since the codec is actually used, we open it - int err = avcodec_open2(this->codec_ctx, codec, NULL); + if (codec == cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS) { + // without this, there's just noise + int err = avcodec_open2(this->codec_ctx, avcodec, NULL); assert(err >= 0); } - this->out_stream = avformat_new_stream(this->ofmt_ctx, raw ? codec : NULL); + this->out_stream = avformat_new_stream(this->ofmt_ctx, raw ? avcodec : NULL); assert(this->out_stream); int err = avio_open(&this->ofmt_ctx->pb, this->vid_path.c_str(), AVIO_FLAG_WRITE); @@ -64,7 +65,7 @@ void VideoWriter::write(uint8_t *data, int len, long long timestamp, bool codecc if (remuxing) { if (codecconfig) { - if (data) { + if (len > 0) { codec_ctx->extradata = (uint8_t*)av_mallocz(len + AV_INPUT_BUFFER_PADDING_SIZE); codec_ctx->extradata_size = len; memcpy(codec_ctx->extradata, data, len); diff --git a/selfdrive/loggerd/video_writer.h b/selfdrive/loggerd/encoder/video_writer.h similarity index 80% rename from selfdrive/loggerd/video_writer.h rename to selfdrive/loggerd/encoder/video_writer.h index 8048d93a07..217964e0ef 100644 --- a/selfdrive/loggerd/video_writer.h +++ b/selfdrive/loggerd/encoder/video_writer.h @@ -6,17 +6,19 @@ extern "C" { #include } +#include "cereal/messaging/messaging.h" + class VideoWriter { public: - VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, bool h265, bool raw); + VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, cereal::EncodeIndex::Type codec); void write(uint8_t *data, int len, long long timestamp, bool codecconfig, bool keyframe); ~VideoWriter(); - AVCodecContext *codec_ctx; private: std::string vid_path, lock_path; FILE *of = nullptr; + AVCodecContext *codec_ctx; AVFormatContext *ofmt_ctx; AVStream *out_stream; bool remuxing, raw; diff --git a/selfdrive/loggerd/encoderd.cc b/selfdrive/loggerd/encoderd.cc index ac57d3eea5..18e88ca8bb 100644 --- a/selfdrive/loggerd/encoderd.cc +++ b/selfdrive/loggerd/encoderd.cc @@ -54,12 +54,14 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { // main encoder encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, - cam_info.fps, cam_info.bitrate, cam_info.is_h265, + cam_info.fps, cam_info.bitrate, + cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, buf_info.width, buf_info.height, false)); // qcamera encoder if (cam_info.has_qcamera) { encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, - qcam_info.fps, qcam_info.bitrate, qcam_info.is_h265, + qcam_info.fps, qcam_info.bitrate, + qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, qcam_info.frame_width, qcam_info.frame_height, false)); } } diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 8e488b4a93..5eb7e6b8cd 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -65,13 +65,15 @@ void encoder_thread(LoggerdState *s, const LogCameraInfo &cam_info) { // main encoder encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, - cam_info.fps, cam_info.bitrate, cam_info.is_h265, + cam_info.fps, cam_info.bitrate, + cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, buf_info.width, buf_info.height, cam_info.record)); // qcamera encoder if (cam_info.has_qcamera) { encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, - qcam_info.fps, qcam_info.bitrate, qcam_info.is_h265, - qcam_info.frame_width, qcam_info.frame_height)); + qcam_info.fps, qcam_info.bitrate, + qcam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264, + qcam_info.frame_width, qcam_info.frame_height, true)); } } diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index ec014649a8..447c4fb4c9 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -22,14 +22,14 @@ #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/encoder/encoder.h" #include "selfdrive/loggerd/logger.h" #ifdef QCOM2 -#include "selfdrive/loggerd/v4l_encoder.h" +#include "selfdrive/loggerd/encoder/v4l_encoder.h" #define Encoder V4LEncoder #else -#include "selfdrive/loggerd/raw_logger.h" -#define Encoder RawLogger +#include "selfdrive/loggerd/encoder/ffmpeg_encoder.h" +#define Encoder FfmpegEncoder #endif constexpr int MAIN_FPS = 20; diff --git a/selfdrive/loggerd/raw_logger.h b/selfdrive/loggerd/raw_logger.h deleted file mode 100644 index 14c4a61ea0..0000000000 --- a/selfdrive/loggerd/raw_logger.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -extern "C" { -#include -#include -#include -} - -#include "selfdrive/loggerd/encoder.h" -#include "selfdrive/loggerd/loggerd.h" -#include "selfdrive/loggerd/video_writer.h" - -class RawLogger : public VideoEncoder { - public: - RawLogger(const char* filename, CameraType type, int in_width, int in_height, int fps, - int bitrate, bool h265, int out_width, int out_height, bool write = true); - ~RawLogger(); - int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, VisionIpcBufExtra *extra); - void encoder_open(const char* path); - void encoder_close(); - -private: - const char* filename; - //bool write; - int fps; - int counter = 0; - bool is_open = false; - - int in_width_, in_height_; - - AVFrame *frame = NULL; - std::vector downscale_buf; - - VideoWriter *writer = NULL; -}; diff --git a/selfdrive/loggerd/remote_encoder.cc b/selfdrive/loggerd/remote_encoder.cc index c79595b0fe..964cd561f0 100644 --- a/selfdrive/loggerd/remote_encoder.cc +++ b/selfdrive/loggerd/remote_encoder.cc @@ -40,7 +40,7 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct re.writer.reset(new VideoWriter(s->segment_path, cam_info.filename, !cam_info.is_h265, cam_info.frame_width, cam_info.frame_height, - cam_info.fps, cam_info.is_h265, false)); + cam_info.fps, cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264)); // write the header auto header = edata.getHeader(); re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); diff --git a/selfdrive/loggerd/remote_encoder.h b/selfdrive/loggerd/remote_encoder.h index 6fc91a2209..79e628f514 100644 --- a/selfdrive/loggerd/remote_encoder.h +++ b/selfdrive/loggerd/remote_encoder.h @@ -1,5 +1,4 @@ -#include "selfdrive/loggerd/video_writer.h" -#define V4L2_BUF_FLAG_KEYFRAME 0x00000008 +#include "selfdrive/loggerd/encoder/video_writer.h" struct RemoteEncoder { std::unique_ptr writer; diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index c39ac955e6..7b6f755ea7 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -71,7 +71,7 @@ def decoder(addr, sock_name, vipc_server, vst, nvidia): assert len(frames) == 1 img_yuv = frames[0].to_ndarray(format=av.video.format.VideoFormat('yuv420p')) - vipc_server.send(vst, img_yuv.flatten().data, cnt, 0, 0) + vipc_server.send(vst, img_yuv.flatten().data, cnt, cnt*1e9/20, cnt*1e9/20) cnt += 1 pc_latency = (time.monotonic()-time_q[0])*1000 From bd0cc655fbbfdafc0ef081be8558b4c773e76eda Mon Sep 17 00:00:00 2001 From: George Hotz <72895+geohot@users.noreply.github.com> Date: Tue, 10 May 2022 16:53:47 -0700 Subject: [PATCH 077/391] encoderd: support remote encoder behind env var (#24490) * remote encoder * remote encoder on PC, fix type Co-authored-by: Comma Device --- selfdrive/loggerd/loggerd.cc | 10 +++++++--- selfdrive/loggerd/remote_encoder.cc | 30 ++++++++++++++--------------- 2 files changed, 21 insertions(+), 19 deletions(-) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 5eb7e6b8cd..9462abba8f 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -1,6 +1,6 @@ #include "selfdrive/loggerd/loggerd.h" #include "selfdrive/loggerd/remote_encoder.h" -bool USE_REMOTE_ENCODER = false; +bool env_remote_encoder = getenv("REMOTE_ENCODER") != NULL; ExitHandler do_exit; @@ -202,7 +202,7 @@ void loggerd_thread() { // subscribe to all socks for (const auto& it : services) { - const bool encoder = USE_REMOTE_ENCODER & (strcmp(it.name+strlen(it.name)-strlen("EncodeData"), "EncodeData") == 0); + const bool encoder = env_remote_encoder && (strcmp(it.name+strlen(it.name)-strlen("EncodeData"), "EncodeData") == 0); if (!it.should_log && !encoder) continue; LOGD("logging %s (on port %d)", it.name, it.port); @@ -228,7 +228,11 @@ void loggerd_thread() { std::vector encoder_threads; for (const auto &cam : cameras_logged) { if (cam.enable) { - encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); + if (env_remote_encoder) { + if (cam.has_qcamera) { s.max_waiting++; } + } else { + encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); + } if (cam.trigger_rotate) s.max_waiting++; } } diff --git a/selfdrive/loggerd/remote_encoder.cc b/selfdrive/loggerd/remote_encoder.cc index 964cd561f0..c640ab5d6c 100644 --- a/selfdrive/loggerd/remote_encoder.cc +++ b/selfdrive/loggerd/remote_encoder.cc @@ -7,11 +7,17 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct ((name == "qRoadEncodeData") ? qcam_info : cameras_logged[0])); if (!cam_info.record) return 0; // TODO: handle this by not subscribing + // rotation happened, process the queue (happens before the current message) int bytes_count = 0; + if (re.logger_segment != s->rotate_segment) { + re.logger_segment = s->rotate_segment; + for (auto &qmsg: re.q) { + bytes_count += handle_encoder_msg(s, qmsg, name, re); + } + re.q.clear(); + } - // TODO: AlignedBuffer is making a copy and allocing - //AlignedBuffer aligned_buf; - //capnp::FlatArrayMessageReader cmsg(aligned_buf.align(msg->getData(), msg->getSize())); + // extract the message capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize())); auto event = cmsg.getRoot(); auto edata = (name == "driverEncodeData") ? event.getDriverEncodeData() : @@ -20,15 +26,6 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct auto idx = edata.getIdx(); auto flags = idx.getFlags(); - // rotation happened, process the queue (happens before the current message) - if (re.logger_segment != s->rotate_segment) { - re.logger_segment = s->rotate_segment; - for (auto &qmsg: re.q) { - bytes_count += handle_encoder_msg(s, qmsg, name, re); - } - re.q.clear(); - } - if (!re.writer) { // only create on iframe if (flags & V4L2_BUF_FLAG_KEYFRAME) { @@ -38,9 +35,8 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct re.dropped_frames = 0; } re.writer.reset(new VideoWriter(s->segment_path, - cam_info.filename, !cam_info.is_h265, - cam_info.frame_width, cam_info.frame_height, - cam_info.fps, cam_info.is_h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264)); + cam_info.filename, idx.getType() != cereal::EncodeIndex::Type::FULL_H_E_V_C, + cam_info.frame_width, cam_info.frame_height, cam_info.fps, idx.getType())); // write the header auto header = edata.getHeader(); re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); @@ -74,8 +70,10 @@ int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct if (name == "roadEncodeData") { evt.setRoadEncodeIdx(idx); } auto new_msg = bmsg.toBytes(); logger_log(&s->logger, (uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? - delete msg; bytes_count += new_msg.size(); + + // this frees the message + delete msg; } return bytes_count; From 4b063a02462f81e60e1fb7a2d7409639a6d00ba4 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Tue, 10 May 2022 19:51:18 -0700 Subject: [PATCH 078/391] pj: add fan rpm to thermal layout --- tools/plotjuggler/layouts/thermal_debug.xml | 47 ++++++++++++--------- 1 file changed, 27 insertions(+), 20 deletions(-) diff --git a/tools/plotjuggler/layouts/thermal_debug.xml b/tools/plotjuggler/layouts/thermal_debug.xml index fbb89ddcf4..cebda81753 100644 --- a/tools/plotjuggler/layouts/thermal_debug.xml +++ b/tools/plotjuggler/layouts/thermal_debug.xml @@ -1,12 +1,12 @@ - - + + - + - - + + @@ -19,8 +19,8 @@ - - + + @@ -29,32 +29,39 @@ - - + + - + - - + + - - - + + + + + + + + + + - + - - + + @@ -63,8 +70,8 @@ - - + + From 67e60efd18155b80384ca9f161fb2a78e8735113 Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 May 2022 14:20:34 -0700 Subject: [PATCH 079/391] remove now unused LastPeripheralPandaType param --- selfdrive/boardd/boardd.cc | 2 -- selfdrive/common/params.cc | 1 - 2 files changed, 3 deletions(-) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index 4af69ec271..fdce7bab5f 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -646,8 +646,6 @@ void boardd_main_thread(std::vector serials) { Panda *peripheral_panda = pandas[0]; std::vector threads; - Params().put("LastPeripheralPandaType", std::to_string((int) peripheral_panda->get_hw_type())); - threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr); threads.emplace_back(peripheral_control_thread, peripheral_panda); threads.emplace_back(pigeon_thread, peripheral_panda); diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index c294c48dfe..f3c599a36a 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -132,7 +132,6 @@ std::unordered_map keys = { {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, - {"LastPeripheralPandaType", PERSISTENT}, {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, {"LastSystemShutdown", CLEAR_ON_MANAGER_START}, {"LastUpdateException", CLEAR_ON_MANAGER_START}, From d2d3b7b823bac0d24e2136f7a97c3aa4c6d9ae47 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 11 May 2022 15:03:05 -0700 Subject: [PATCH 080/391] process replay: automatically push refs on fail (#24414) * test failure() * let's just change a tune here * debug revert * debug * use current commit, not ref_commit fix * need to figure out better place for this * quick test * test without upload * temp * use azure token * fixes * shouldn't need this * debug * debug * not getting anything? * does this mean nothing gets envvars? * add azure token to docker environment variables * quote * move back * clean up a bit * more clean up * like this sorting better * replace flags with CI and clean up * test FULL_TEST and minimalize diff a bit * now test all * revert tests comments * remove flags * revert this revert this * now make it fail * now update ref_commit to last commit (make sure we can re-start this test if we commit before last one finishes uploading) * fix fix fix fix * bad commit * why is it not throwing an exception? * debug * URLFile returns empty bytes if using cache and remote file doesn't exist * we always need to download anyway * debug... * duh, wrong file. but neither should have it * add that back and just check explicitly * check both * clean up and make a diff * stylize * see if this is a better diff on files changed * update refs * revert changes * only for owners or members * if we have token access * if we have token access * if we have token access * move up * clean up * revert * move update refs to test_processes * clean up * update messages * update msg * update README and delete update_refs * this isn't possible to reach anymore * fix readme * better help message better help message better help message * only show basename when uploading, only if failed to find * test diff * fix printing old ref commit * change to using * update refs * Revert "update refs" This reverts commit 2e352a736a6de68e2c7064daa4e2e9409ce77686. * revert * ref refers to reference commit/logs, cur refers to current logs/commit (future ref) * like for better * Apply suggestions from code review Co-authored-by: Adeeb Shihadeh * Update selfdrive/test/process_replay/test_processes.py * every time lol Co-authored-by: Adeeb Shihadeh --- .github/workflows/selfdrive_tests.yaml | 6 ++ selfdrive/test/openpilotci.py | 6 +- selfdrive/test/process_replay/README.md | 28 +++++- .../test/process_replay/process_replay.py | 1 + .../test/process_replay/test_processes.py | 95 ++++++++++++------- selfdrive/test/process_replay/update_refs.py | 38 -------- 6 files changed, 96 insertions(+), 78 deletions(-) delete mode 100755 selfdrive/test/process_replay/update_refs.py diff --git a/.github/workflows/selfdrive_tests.yaml b/.github/workflows/selfdrive_tests.yaml index 752a5ec357..feb7cfa1d5 100644 --- a/.github/workflows/selfdrive_tests.yaml +++ b/.github/workflows/selfdrive_tests.yaml @@ -8,6 +8,7 @@ on: env: BASE_IMAGE: openpilot-base DOCKER_REGISTRY: ghcr.io/commaai + AZURE_TOKEN: ${{ secrets.AZURE_COMMADATACI_OPENPILOTCI_TOKEN }} DOCKER_LOGIN: docker login ghcr.io -u adeebshihadeh -p ${{ secrets.CONTAINER_TOKEN }} BUILD: | @@ -316,6 +317,11 @@ jobs: ${{ env.RUN }} "scons -j$(nproc) && \ FILEREADER_CACHE=1 CI=1 coverage run selfdrive/test/process_replay/test_processes.py && \ coverage xml" + - name: Upload reference logs + if: ${{ failure() && github.event_name == 'pull_request' && github.repository == 'commaai/openpilot' && env.AZURE_TOKEN != '' }} + run: | + ${{ env.RUN }} "scons -j$(nproc) && \ + CI=1 AZURE_TOKEN='$AZURE_TOKEN' python selfdrive/test/process_replay/test_processes.py --upload-only" - name: "Upload coverage to Codecov" uses: codecov/codecov-action@v2 - name: Print diff diff --git a/selfdrive/test/openpilotci.py b/selfdrive/test/openpilotci.py index 6483b6717f..1d1b6ec423 100755 --- a/selfdrive/test/openpilotci.py +++ b/selfdrive/test/openpilotci.py @@ -4,17 +4,18 @@ import sys import subprocess BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" - TOKEN_PATH = "/data/azure_token" + def get_url(route_name, segment_num, log_type="rlog"): ext = "hevc" if log_type.endswith('camera') else "bz2" return BASE_URL + f"{route_name.replace('|', '/')}/{segment_num}/{log_type}.{ext}" + def upload_file(path, name): from azure.storage.blob import BlockBlobService # pylint: disable=import-error - sas_token = None + sas_token = os.environ.get("AZURE_TOKEN", None) if os.path.isfile(TOKEN_PATH): sas_token = open(TOKEN_PATH).read().strip() @@ -25,6 +26,7 @@ def upload_file(path, name): service.create_blob_from_path("openpilotci", name, path) return "https://commadataci.blob.core.windows.net/openpilotci/" + name + if __name__ == "__main__": for f in sys.argv[1:]: name = os.path.basename(f) diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index 3add95f0a0..e760e4e135 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -1,4 +1,4 @@ -# process replay +# Process replay Process replay is a regression test designed to identify any changes in the output of a process. This test replays a segment through individual processes and compares the output to a known good replay. Each make is represented in the test with a segment. @@ -12,14 +12,34 @@ Currently the following processes are tested: * radard * plannerd * calibrationd +* dmonitoringd +* locationd +* paramsd * ubloxd +### Usage +``` +Usage: test_processes.py [-h] [--whitelist-procs PROCS] [--whitelist-cars CARS] [--blacklist-procs PROCS] + [--blacklist-cars CARS] [--ignore-fields FIELDS] [--ignore-msgs MSGS] [--update-refs] [--upload-only] +Regression test to identify changes in a process's output +optional arguments: + -h, --help show this help message and exit + --whitelist-procs PROCS Whitelist given processes from the test (e.g. controlsd) + --whitelist-cars WHITELIST_CARS Whitelist given cars from the test (e.g. HONDA) + --blacklist-procs BLACKLIST_PROCS Blacklist given processes from the test (e.g. controlsd) + --blacklist-cars BLACKLIST_CARS Blacklist given cars from the test (e.g. HONDA) + --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. carState.events) + --ignore-msgs IGNORE_MSGS Msgs to ignore (e.g. carEvents) + --update-refs Updates reference logs using current commit + --upload-only Skips testing processes and uploads logs from previous test run +``` + ## Forks -openpilot forks can use this test with their own reference logs +openpilot forks can use this test with their own reference logs, by default `test_proccess.py` saves logs locally. To generate new logs: -`./update_refs.py --no-upload` +`./test_processes.py` -Then, check in the new logs using git-lfs. Make sure to also include the updated `ref_commit` file. +Then, check in the new logs using git-lfs. Make sure to also update the `ref_commit` file to the current commit. diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index e06d8198e4..c1b89713f3 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -24,6 +24,7 @@ from selfdrive.manager.process_config import managed_processes NUMPY_TOLERANCE = 1e-7 CI = "CI" in os.environ TIMEOUT = 15 +PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__)) ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'init_callback', 'should_recv_callback', 'tolerance', 'fake_pubsubmaster', 'submaster_config'], defaults=({},)) diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 4f1f11eaf7..0a8fb9b454 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -5,9 +5,10 @@ import sys from typing import Any from selfdrive.car.car_helpers import interface_names -from selfdrive.test.openpilotci import get_url -from selfdrive.test.process_replay.compare_logs import compare_logs -from selfdrive.test.process_replay.process_replay import CONFIGS, replay_process, check_enabled +from selfdrive.test.openpilotci import get_url, upload_file +from selfdrive.test.process_replay.compare_logs import compare_logs, save_log +from selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, check_enabled, replay_process +from selfdrive.version import get_commit from tools.lib.logreader import LogReader @@ -50,32 +51,31 @@ segments = [ excluded_interfaces = ["mock", "ford", "mazda", "tesla"] BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" +REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") -# run the full test (including checks) when no args given -FULL_TEST = len(sys.argv) <= 1 - -def test_process(cfg, lr, cmp_log_fn, ignore_fields=None, ignore_msgs=None): +def test_process(cfg, lr, ref_log_fn, ignore_fields=None, ignore_msgs=None): if ignore_fields is None: ignore_fields = [] if ignore_msgs is None: ignore_msgs = [] - cmp_log_path = cmp_log_fn if os.path.exists(cmp_log_fn) else BASE_URL + os.path.basename(cmp_log_fn) - cmp_log_msgs = list(LogReader(cmp_log_path)) + ref_log_path = ref_log_fn if os.path.exists(ref_log_fn) else BASE_URL + os.path.basename(ref_log_fn) + ref_log_msgs = list(LogReader(ref_log_path)) log_msgs = replay_process(cfg, lr) # check to make sure openpilot is engaged in the route if cfg.proc_name == "controlsd": if not check_enabled(log_msgs): - segment = cmp_log_fn.split("/")[-1].split("_")[0] + segment = ref_log_fn.split("/")[-1].split("_")[0] raise Exception(f"Route never enabled: {segment}") try: - return compare_logs(cmp_log_msgs, log_msgs, ignore_fields+cfg.ignore, ignore_msgs, cfg.tolerance) + return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs except Exception as e: - return str(e) + return str(e), log_msgs + def format_diff(results, ref_commit): diff1, diff2 = "", "" @@ -106,47 +106,57 @@ def format_diff(results, ref_commit): failed = True return diff1, diff2, failed -if __name__ == "__main__": +if __name__ == "__main__": parser = argparse.ArgumentParser(description="Regression test to identify changes in a process's output") # whitelist has precedence over blacklist in case both are defined parser.add_argument("--whitelist-procs", type=str, nargs="*", default=[], - help="Whitelist given processes from the test (e.g. controlsd)") + help="Whitelist given processes from the test (e.g. controlsd)") parser.add_argument("--whitelist-cars", type=str, nargs="*", default=[], - help="Whitelist given cars from the test (e.g. HONDA)") + help="Whitelist given cars from the test (e.g. HONDA)") parser.add_argument("--blacklist-procs", type=str, nargs="*", default=[], - help="Blacklist given processes from the test (e.g. controlsd)") + help="Blacklist given processes from the test (e.g. controlsd)") parser.add_argument("--blacklist-cars", type=str, nargs="*", default=[], - help="Blacklist given cars from the test (e.g. HONDA)") + help="Blacklist given cars from the test (e.g. HONDA)") parser.add_argument("--ignore-fields", type=str, nargs="*", default=[], - help="Extra fields or msgs to ignore (e.g. carState.events)") + help="Extra fields or msgs to ignore (e.g. carState.events)") parser.add_argument("--ignore-msgs", type=str, nargs="*", default=[], - help="Msgs to ignore (e.g. carEvents)") + help="Msgs to ignore (e.g. carEvents)") + parser.add_argument("--update-refs", action="store_true", + help="Updates reference logs using current commit") + parser.add_argument("--upload-only", action="store_true", + help="Skips testing processes and uploads logs from previous test run") args = parser.parse_args() - cars_whitelisted = len(args.whitelist_cars) > 0 - procs_whitelisted = len(args.whitelist_procs) > 0 + full_test = all(len(x) == 0 for x in (args.whitelist_procs, args.whitelist_cars, args.blacklist_procs, args.blacklist_cars, args.ignore_fields, args.ignore_msgs)) + upload = args.update_refs or args.upload_only + + if upload: + assert full_test, "Need to run full test when updating refs" - process_replay_dir = os.path.dirname(os.path.abspath(__file__)) try: - ref_commit = open(os.path.join(process_replay_dir, "ref_commit")).read().strip() + ref_commit = open(REF_COMMIT_FN).read().strip() except FileNotFoundError: - print("couldn't find reference commit") + print("Couldn't find reference commit") sys.exit(1) + cur_commit = get_commit() + if cur_commit is None: + raise Exception("Couldn't get current commit") + print(f"***** testing against commit {ref_commit} *****") # check to make sure all car brands are tested - if FULL_TEST: + if full_test: tested_cars = {c.lower() for c, _ in segments} untested = (set(interface_names) - set(excluded_interfaces)) - tested_cars assert len(untested) == 0, f"Cars missing routes: {str(untested)}" results: Any = {} for car_brand, segment in segments: - if (cars_whitelisted and car_brand.upper() not in args.whitelist_cars) or \ - (not cars_whitelisted and car_brand.upper() in args.blacklist_cars): + if (len(args.whitelist_cars) and car_brand.upper() not in args.whitelist_cars) or \ + (not len(args.whitelist_cars) and car_brand.upper() in args.blacklist_cars): continue print(f"***** testing route segment {segment} *****\n") @@ -157,23 +167,40 @@ if __name__ == "__main__": lr = LogReader(get_url(r, n)) for cfg in CONFIGS: - if (procs_whitelisted and cfg.proc_name not in args.whitelist_procs) or \ - (not procs_whitelisted and cfg.proc_name in args.blacklist_procs): + if (len(args.whitelist_procs) and cfg.proc_name not in args.whitelist_procs) or \ + (not len(args.whitelist_procs) and cfg.proc_name in args.blacklist_procs): continue - cmp_log_fn = os.path.join(process_replay_dir, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") - results[segment][cfg.proc_name] = test_process(cfg, lr, cmp_log_fn, args.ignore_fields, args.ignore_msgs) + cur_log_fn = os.path.join(PROC_REPLAY_DIR, f"{segment}_{cfg.proc_name}_{cur_commit}.bz2") + if not args.upload_only: + ref_log_fn = os.path.join(PROC_REPLAY_DIR, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") + results[segment][cfg.proc_name], log_msgs = test_process(cfg, lr, ref_log_fn, args.ignore_fields, args.ignore_msgs) + + # save logs so we can upload when updating refs + save_log(cur_log_fn, log_msgs) + + if upload: + print(f'Uploading: {os.path.basename(cur_log_fn)}') + assert os.path.exists(cur_log_fn), f"Cannot find log to upload: {cur_log_fn}" + upload_file(cur_log_fn, os.path.basename(cur_log_fn)) + os.remove(cur_log_fn) diff1, diff2, failed = format_diff(results, ref_commit) - with open(os.path.join(process_replay_dir, "diff.txt"), "w") as f: + with open(os.path.join(PROC_REPLAY_DIR, "diff.txt"), "w") as f: f.write(diff2) print(diff1) if failed: print("TEST FAILED") - print("\n\nTo update the reference logs for this test run:") - print("./update_refs.py") + if not upload: + print("\n\nTo push the new reference logs for this commit run:") + print("./test_processes.py --upload-only") else: print("TEST SUCCEEDED") + if upload: + with open(REF_COMMIT_FN, "w") as f: + f.write(cur_commit) + print(f"\n\nUpdated reference logs for commit: {cur_commit}") + sys.exit(int(failed)) diff --git a/selfdrive/test/process_replay/update_refs.py b/selfdrive/test/process_replay/update_refs.py deleted file mode 100755 index 0a3d95e714..0000000000 --- a/selfdrive/test/process_replay/update_refs.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys - -from selfdrive.test.openpilotci import upload_file, get_url -from selfdrive.test.process_replay.compare_logs import save_log -from selfdrive.test.process_replay.process_replay import replay_process, CONFIGS -from selfdrive.test.process_replay.test_processes import segments -from selfdrive.version import get_commit -from tools.lib.logreader import LogReader - -if __name__ == "__main__": - - no_upload = "--no-upload" in sys.argv - - process_replay_dir = os.path.dirname(os.path.abspath(__file__)) - ref_commit_fn = os.path.join(process_replay_dir, "ref_commit") - - ref_commit = get_commit() - if ref_commit is None: - raise Exception("couldn't get ref commit") - with open(ref_commit_fn, "w") as f: - f.write(ref_commit) - - for car_brand, segment in segments: - r, n = segment.rsplit("--", 1) - lr = LogReader(get_url(r, n)) - - for cfg in CONFIGS: - log_msgs = replay_process(cfg, lr) - log_fn = os.path.join(process_replay_dir, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") - save_log(log_fn, log_msgs) - - if not no_upload: - upload_file(log_fn, os.path.basename(log_fn)) - os.remove(log_fn) - - print("done") From dabcfd266e4e6e632064b592409fc63f543e5dbb Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 11 May 2022 15:59:08 -0700 Subject: [PATCH 081/391] car info: function that sorts all car info into tiers (#24498) * base function that returns all car info sorted by make model * don't need to pass it in quite yet --- scripts/count_cars.py | 6 ++---- selfdrive/car/docs.py | 23 +++++++++++++++-------- selfdrive/car/docs_definitions.py | 1 + selfdrive/car/tests/test_docs.py | 23 +++++++++++------------ 4 files changed, 29 insertions(+), 24 deletions(-) diff --git a/scripts/count_cars.py b/scripts/count_cars.py index 46d8499461..25bad2c9b4 100755 --- a/scripts/count_cars.py +++ b/scripts/count_cars.py @@ -2,12 +2,10 @@ from collections import Counter from pprint import pprint -from selfdrive.car.docs import get_tier_car_info +from selfdrive.car.docs import get_all_car_info if __name__ == "__main__": - tiers = get_tier_car_info() - cars = [car for tier_cars in tiers.values() for car in tier_cars] - + cars = get_all_car_info() make_count = Counter(l.make for l in cars) print("\n", "*" * 20, len(cars), "total", "*" * 20, "\n") pprint(make_count) diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index a39e8df805..64d4dbfef4 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -26,9 +26,8 @@ CARS_MD_OUT = os.path.join(BASEDIR, "docs", "CARS.md") CARS_MD_TEMPLATE = os.path.join(BASEDIR, "selfdrive", "car", "CARS_template.md") -def get_tier_car_info() -> Dict[Tier, List[CarInfo]]: - tier_car_info: Dict[Tier, List[CarInfo]] = {tier: [] for tier in Tier} - +def get_all_car_info() -> List[CarInfo]: + all_car_info: List[CarInfo] = [] for models in get_interface_attr("CAR_INFO").values(): for model, car_info in models.items(): # Hyundai exception: those with radar have openpilot longitudinal @@ -43,8 +42,16 @@ def get_tier_car_info() -> Dict[Tier, List[CarInfo]]: car_info = (car_info,) for _car_info in car_info: - _car_info.init(CP, non_tested_cars, ALL_FOOTNOTES) - tier_car_info[_car_info.tier].append(_car_info) + all_car_info.append(_car_info.init(CP, non_tested_cars, ALL_FOOTNOTES)) + + # Sort cars by make and model + year + return natsorted(all_car_info, key=lambda car: (car.make + car.model).lower()) + + +def sort_by_tier(all_car_info: List[CarInfo]) -> Dict[Tier, List[CarInfo]]: + tier_car_info: Dict[Tier, List[CarInfo]] = {tier: [] for tier in Tier} + for car_info in all_car_info: + tier_car_info[car_info.tier].append(car_info) # Sort cars by make and model + year for tier, cars in tier_car_info.items(): @@ -53,12 +60,12 @@ def get_tier_car_info() -> Dict[Tier, List[CarInfo]]: return tier_car_info -def generate_cars_md(tier_car_info: Dict[Tier, List[CarInfo]], template_fn: str) -> str: +def generate_cars_md(all_car_info: List[CarInfo], template_fn: str) -> str: with open(template_fn, "r") as f: template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) footnotes = [fn.value.text for fn in ALL_FOOTNOTES] - return template.render(tiers=tier_car_info, footnotes=footnotes, Star=Star, Column=Column) + return template.render(tiers=sort_by_tier(all_car_info), footnotes=footnotes, Star=Star, Column=Column) if __name__ == "__main__": @@ -70,5 +77,5 @@ if __name__ == "__main__": args = parser.parse_args() with open(args.out, 'w') as f: - f.write(generate_cars_md(get_tier_car_info(), args.template)) + f.write(generate_cars_md(get_all_car_info(), args.template)) print(f"Generated and written to {args.out}") diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index e406422981..1ca2205ce5 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -91,6 +91,7 @@ class CarInfo: self.row[column] = footnote.value.star self.tier = {5: Tier.GOLD, 4: Tier.SILVER}.get(list(self.row.values()).count(Star.FULL), Tier.BRONZE) + return self @no_type_check def get_column(self, column: Column, star_icon: str, footnote_tag: str) -> str: diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index 6c7ae1fdac..1530eb18af 100755 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -1,15 +1,15 @@ #!/usr/bin/env python3 import unittest -from selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE, generate_cars_md, get_tier_car_info +from selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE, generate_cars_md, get_all_car_info class TestCarDocs(unittest.TestCase): def setUp(self): - self.tier_cars = get_tier_car_info() + self.all_cars = get_all_car_info() def test_generator(self): - generated_cars_md = generate_cars_md(self.tier_cars, CARS_MD_TEMPLATE) + generated_cars_md = generate_cars_md(self.all_cars, CARS_MD_TEMPLATE) with open(CARS_MD_OUT, "r") as f: current_cars_md = f.read() @@ -18,15 +18,14 @@ class TestCarDocs(unittest.TestCase): def test_naming_conventions(self): # Asserts market-standard car naming conventions by make - for cars in self.tier_cars.values(): - for car in cars: - if car.car_name == "hyundai": - tokens = car.model.lower().split(" ") - self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`") - self.assertNotIn("hev", tokens, "Use `Hybrid`") - self.assertNotIn("ev", tokens, "Use `Electric`") - if "plug-in hybrid" in car.model.lower(): - self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization") + for car in self.all_cars: + if car.car_name == "hyundai": + tokens = car.model.lower().split(" ") + self.assertNotIn("phev", tokens, "Use `Plug-in Hybrid`") + self.assertNotIn("hev", tokens, "Use `Hybrid`") + self.assertNotIn("ev", tokens, "Use `Electric`") + if "plug-in hybrid" in car.model.lower(): + self.assertIn("Plug-in Hybrid", car.model, "Use correct capitalization") if __name__ == "__main__": From 685802b8602d895869d8d205913007ce83bcb37b Mon Sep 17 00:00:00 2001 From: Adeeb Shihadeh Date: Wed, 11 May 2022 16:30:26 -0700 Subject: [PATCH 082/391] test car models: stricter radar CAN error check (#24497) * test routes: stricter radar CAN error check * bump opendbc * bump again --- opendbc | 2 +- selfdrive/car/tests/test_models.py | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/opendbc b/opendbc index 919154efe2..9564b74d80 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 919154efe2bd07c4dd124d7e6a11a4afc8685f9d +Subproject commit 9564b74d80525c9f289b730febbb2348c529c9cc diff --git a/selfdrive/car/tests/test_models.py b/selfdrive/car/tests/test_models.py index 17044c432d..ff2d49305c 100755 --- a/selfdrive/car/tests/test_models.py +++ b/selfdrive/car/tests/test_models.py @@ -143,11 +143,11 @@ class TestCarModel(unittest.TestCase): assert RI error_cnt = 0 - for msg in self.can_msgs: - radar_data = RI.update((msg.as_builder().to_bytes(),)) - if radar_data is not None: - error_cnt += car.RadarData.Error.canError in radar_data.errors - self.assertLess(error_cnt, 20) + for i, msg in enumerate(self.can_msgs): + rr = RI.update((msg.as_builder().to_bytes(),)) + if rr is not None and i > 50: + error_cnt += car.RadarData.Error.canError in rr.errors + self.assertEqual(error_cnt, 0) def test_panda_safety_rx_valid(self): if self.CP.dashcamOnly: From 433fcc0c716cb354184afc7014056d198ae56a4d Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 11 May 2022 18:02:21 -0700 Subject: [PATCH 083/391] CarInfo: Add harness information (#24085) * Add harness information * test harness enum * add harness info for tucson * update Tucson harness * get rid of development * make global enum * fix * add harness info * add harness info to CARS.md (since we need multiple lines per HKG platform) * revert this * Actively Maintained means something! (aka, to bronze with select VW) * fix caravelle * add harness tooltip on maintained column fix * lol tubaru * always assume harness * update honda harnesses * add Ioniq hybrid 2017-19 harness, todo: not sure * unused import * hmm, did they really switch to the C for 1 year?? * add comment * add comments * adding tooltips should be fine * fix santa fe harness * welcome back, vw * no need for two harness strings * seems fine * fix 19-20 Niro EV harness * these were taking from old database, so assume correct * could be d * pass all car info into template * no more tool tips * these use j533 harnesses * accidentally got removed in merge * also merge issue * don't need these * make harness non-optional --- docs/CARS.md | 17 ++++-- selfdrive/car/body/values.py | 4 +- selfdrive/car/chrysler/values.py | 7 ++- selfdrive/car/docs.py | 3 +- selfdrive/car/docs_definitions.py | 38 +++++++++++- selfdrive/car/gm/values.py | 25 +++++--- selfdrive/car/honda/values.py | 44 +++++++------- selfdrive/car/hyundai/values.py | 93 +++++++++++++++++------------- selfdrive/car/mazda/values.py | 4 +- selfdrive/car/nissan/values.py | 6 +- selfdrive/car/subaru/values.py | 6 +- selfdrive/car/toyota/values.py | 3 +- selfdrive/car/volkswagen/values.py | 24 +++++--- 13 files changed, 176 insertions(+), 98 deletions(-) diff --git a/docs/CARS.md b/docs/CARS.md index d41a112468..7e40120250 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -44,7 +44,9 @@ How We Rate The Cars |Hyundai|Santa Fe 2019-20|All|||||| |Hyundai|Sonata 2020-22|All|||||| |Hyundai|Sonata Hybrid 2020-22|All|||||| -|Kia|Niro Electric 2019-22|All|||||| +|Kia|Niro Electric 2019-20|All|||||| +|Kia|Niro Electric 2021|All|||||| +|Kia|Niro Electric 2022|All|||||| |Kia|Telluride 2020|SCC + LKAS|||||| |Lexus|ES 2019-21|All|||||| |Lexus|ES Hybrid 2019-22|All|||||| @@ -95,12 +97,15 @@ How We Rate The Cars |Hyundai|Sonata 2018-19|SCC + LKAS|||||| |Hyundai|Tucson Diesel 2019|SCC + LKAS|||||| |Kia|Ceed 2019|SCC + LKAS|||||| -|Kia|Forte 2018-21|SCC + LKAS|||||| +|Kia|Forte 2018|SCC + LKAS|||||| +|Kia|Forte 2019-21|SCC + LKAS|||||| |Kia|K5 2021-22|SCC + LFA|||||| -|Kia|Niro Hybrid 2021-22|SCC + LKAS|||||| +|Kia|Niro Hybrid 2021|SCC + LKAS|||||| +|Kia|Niro Hybrid 2022|SCC + LKAS|||||| |Kia|Optima 2019|SCC + LKAS|||||| |Kia|Seltos 2021|SCC + LKAS|||||| -|Kia|Sorento 2018-19|SCC + LKAS|||||| +|Kia|Sorento 2018|SCC + LKAS|||||| +|Kia|Sorento 2019|SCC + LKAS|||||| |Kia|Stinger 2018|SCC + LKAS|||||| |Lexus|CT Hybrid 2017-18|LSS|[3](#footnotes)||||| |Lexus|ES Hybrid 2017-18|LSS|[3](#footnotes)||||| @@ -159,14 +164,14 @@ How We Rate The Cars |Acura|ILX 2016-19|AcuraWatch Plus|||||| |Acura|RDX 2016-18|AcuraWatch Plus|||||| |Acura|RDX 2019-21|All|||||| -|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| +|Cadillac|Escalade ESV 2016[1](#footnotes)|ACC + LKAS|||||| |Chevrolet|Volt 2017-18[1](#footnotes)|Adaptive Cruise|||||| |Chrysler|Pacifica 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica 2020|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise|||||| |Chrysler|Pacifica Hybrid 2019-21|Adaptive Cruise|||||| |Genesis|G90 2018|All|||||| -|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| +|GMC|Acadia 2018[1](#footnotes)|Adaptive Cruise|||||| |Honda|Accord 2018-21|All|||||| |Honda|Accord Hybrid 2018-21|All|||||| |Honda|Civic 2016-18|Honda Sensing|||||| diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py index 04de0ef2e3..a009b40bc9 100644 --- a/selfdrive/car/body/values.py +++ b/selfdrive/car/body/values.py @@ -2,7 +2,7 @@ from typing import Dict from cereal import car from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness Ecu = car.CarParams.Ecu SPEED_FROM_RPM = 0.008587 @@ -18,7 +18,7 @@ class CAR: BODY = "COMMA BODY" CAR_INFO: Dict[str, CarInfo] = { - CAR.BODY: CarInfo("comma body", package="All", good_torque=True), + CAR.BODY: CarInfo("comma body", package="All", good_torque=True, harness=Harness.none), } FW_VERSIONS = { diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index 3716caf5bf..01923f2ae7 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,11 +1,13 @@ from dataclasses import dataclass +from enum import Enum from typing import Dict, List, Union from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness from cereal import car Ecu = car.CarParams.Ecu + class CarControllerParams: STEER_MAX = 261 # 262 faults STEER_DELTA_UP = 3 # 3 is stock. 100 is fine. 200 is too much it seems @@ -20,12 +22,13 @@ class CAR: PACIFICA_2018 = "CHRYSLER PACIFICA 2018" # includes 2017 Pacifica PACIFICA_2020 = "CHRYSLER PACIFICA 2020" JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # includes 2017 Trailhawk - JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk + JEEP_CHEROKEE_2019 = "JEEP GRAND CHEROKEE 2019" # includes 2020 Trailhawk @dataclass class ChryslerCarInfo(CarInfo): package: str = "Adaptive Cruise" + harness: Enum = Harness.fca CAR_INFO: Dict[str, Union[ChryslerCarInfo, List[ChryslerCarInfo]]] = { diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 64d4dbfef4..8fb1547f06 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -65,7 +65,8 @@ def generate_cars_md(all_car_info: List[CarInfo], template_fn: str) -> str: template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) footnotes = [fn.value.text for fn in ALL_FOOTNOTES] - return template.render(tiers=sort_by_tier(all_car_info), footnotes=footnotes, Star=Star, Column=Column) + return template.render(tiers=sort_by_tier(all_car_info), all_car_info=all_car_info, + footnotes=footnotes, Star=Star, Column=Column) if __name__ == "__main__": diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 1ca2205ce5..3046f5c9e3 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -50,13 +50,16 @@ class CarInfo: min_steer_speed: Optional[float] = None min_enable_speed: Optional[float] = None good_torque: bool = False + harness: Optional[Enum] = None def init(self, CP: car.CarParams, non_tested_cars: List[str], all_footnotes: Dict[Enum, int]): # TODO: set all the min steer speeds in carParams and remove this min_steer_speed = CP.minSteerSpeed if self.min_steer_speed is not None: min_steer_speed = self.min_steer_speed - assert CP.minSteerSpeed == 0, f"Minimum steer speed set in both CarInfo and CarParams for {CP.carFingerprint}" + assert CP.minSteerSpeed == 0, f"{CP.carFingerprint}: Minimum steer speed set in both CarInfo and CarParams" + + assert self.harness is not None, f"{CP.carFingerprint}: Need to specify car harness" # TODO: set all the min enable speeds in carParams correctly and remove this min_enable_speed = CP.minEnableSpeed @@ -74,7 +77,7 @@ class CarInfo: Column.FSR_LONGITUDINAL: min_enable_speed <= 0., Column.FSR_STEERING: min_steer_speed <= 0., Column.STEERING_TORQUE: self.good_torque, - Column.MAINTAINED: CP.carFingerprint not in non_tested_cars, + Column.MAINTAINED: CP.carFingerprint not in non_tested_cars and self.harness is not Harness.none, } if CP.notCar: @@ -104,3 +107,34 @@ class CarInfo: item += footnote_tag.format(self.all_footnotes[footnote]) return item + + +class Harness(Enum): + nidec = "Honda Nidec" + bosch = "Honda Bosch" + toyota = "Toyota" + subaru = "Subaru" + fca = "FCA" + vw = "VW" + j533 = "J533" + hyundai_a = "Hyundai A" + hyundai_b = "Hyundai B" + hyundai_c = "Hyundai C" + hyundai_d = "Hyundai D" + hyundai_e = "Hyundai E" + hyundai_f = "Hyundai F" + hyundai_g = "Hyundai G" + hyundai_h = "Hyundai H" + hyundai_i = "Hyundai I" + hyundai_j = "Hyundai J" + hyundai_k = "Hyundai K" + hyundai_l = "Hyundai L" + hyundai_m = "Hyundai M" + hyundai_n = "Hyundai N" + hyundai_o = "Hyundai O" + custom = "Developer" + obd_ii = "OBD-II" + nissan_a = "Nissan A" + nissan_b = "Nissan B" + mazda = "Mazda" + none = "None" diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index 65d42579d3..8ef33e8297 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -1,9 +1,10 @@ +from dataclasses import dataclass from enum import Enum from typing import Dict, List, Union from cereal import car from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column +from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness Ecu = car.CarParams.Ecu @@ -62,14 +63,20 @@ class Footnote(Enum): Column.MODEL) -CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { - CAR.HOLDEN_ASTRA: CarInfo("Holden Astra 2017", "Adaptive Cruise"), - CAR.VOLT: CarInfo("Chevrolet Volt 2017-18", "Adaptive Cruise", footnotes=[Footnote.OBD_II], min_enable_speed=0), - CAR.CADILLAC_ATS: CarInfo("Cadillac ATS Premium Performance 2018", "Adaptive Cruise"), - CAR.MALIBU: CarInfo("Chevrolet Malibu Premier 2017", "Adaptive Cruise"), - CAR.ACADIA: CarInfo("GMC Acadia 2018", "Adaptive Cruise", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo", footnotes=[Footnote.OBD_II]), - CAR.BUICK_REGAL: CarInfo("Buick Regal Essence 2018", "Adaptive Cruise"), - CAR.ESCALADE_ESV: CarInfo("Cadillac Escalade ESV 2016", "ACC + LKAS", footnotes=[Footnote.OBD_II]), +@dataclass +class GMCarInfo(CarInfo): + package: str = "Adaptive Cruise" + harness: Enum = Harness.none + + +CAR_INFO: Dict[str, Union[GMCarInfo, List[GMCarInfo]]] = { + CAR.HOLDEN_ASTRA: GMCarInfo("Holden Astra 2017", harness=Harness.custom), + CAR.VOLT: GMCarInfo("Chevrolet Volt 2017-18", footnotes=[Footnote.OBD_II], min_enable_speed=0, harness=Harness.custom), + CAR.CADILLAC_ATS: GMCarInfo("Cadillac ATS Premium Performance 2018"), + CAR.MALIBU: GMCarInfo("Chevrolet Malibu Premier 2017", harness=Harness.custom), + CAR.ACADIA: GMCarInfo("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo", footnotes=[Footnote.OBD_II]), + CAR.BUICK_REGAL: GMCarInfo("Buick Regal Essence 2018"), + CAR.ESCALADE_ESV: GMCarInfo("Cadillac Escalade ESV 2016", "ACC + LKAS", footnotes=[Footnote.OBD_II]), } diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 64c7dd8420..d575c0518d 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -5,7 +5,7 @@ from typing import Dict, List, Union from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column +from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness Ecu = car.CarParams.Ecu VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -108,31 +108,31 @@ class HondaCarInfo(CarInfo): CAR_INFO: Dict[str, Union[HondaCarInfo, List[HondaCarInfo]]] = { CAR.ACCORD: [ - HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarInfo("Honda Accord 2018-21", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + HondaCarInfo("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), ], - CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18"), + CAR.ACCORDH: HondaCarInfo("Honda Accord Hybrid 2018-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.CIVIC: HondaCarInfo("Honda Civic 2016-18", harness=Harness.nidec), CAR.CIVIC_BOSCH: [ - HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), - HondaCarInfo("Honda Civic Hatchback 2017-21"), + HondaCarInfo("Honda Civic 2019-20", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS, harness=Harness.bosch), + HondaCarInfo("Honda Civic Hatchback 2017-21", harness=Harness.bosch), ], - CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS), - CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring"), - CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21"), + CAR.ACURA_ILX: HondaCarInfo("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS, harness=Harness.nidec), + CAR.CRV: HondaCarInfo("Honda CR-V 2015-16", "Touring", harness=Harness.nidec), + CAR.CRV_5G: HondaCarInfo("Honda CR-V 2017-21", harness=Harness.bosch), # CAR.CRV_EU: HondaCarInfo("Honda CR-V EU", "Touring"), # Euro version of CRV Touring - CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19"), - CAR.FIT: HondaCarInfo("Honda Fit 2018-19"), - CAR.FREED: HondaCarInfo("Honda Freed 2020"), - CAR.HRV: HondaCarInfo("Honda HR-V 2019-20"), - CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0.), - CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus"), - CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21"), - CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All"), - CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22"), - CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS), - CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS), + CAR.CRV_HYBRID: HondaCarInfo("Honda CR-V Hybrid 2017-19", harness=Harness.bosch), + CAR.FIT: HondaCarInfo("Honda Fit 2018-19", harness=Harness.nidec), + CAR.FREED: HondaCarInfo("Honda Freed 2020", harness=Harness.nidec), + CAR.HRV: HondaCarInfo("Honda HR-V 2019-20", harness=Harness.nidec), + CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20", min_steer_speed=0., harness=Harness.nidec), + CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", harness=Harness.nidec), + CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.PILOT: HondaCarInfo("Honda Pilot 2016-21", harness=Harness.nidec), + CAR.PASSPORT: HondaCarInfo("Honda Passport 2019-21", "All", harness=Harness.nidec), + CAR.RIDGELINE: HondaCarInfo("Honda Ridgeline 2017-22", harness=Harness.nidec), + CAR.INSIGHT: HondaCarInfo("Honda Insight 2019-21", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), + CAR.HONDA_E: HondaCarInfo("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS, harness=Harness.bosch), } diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index 1a20ab6d6b..c1a3b534c8 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -4,7 +4,7 @@ from typing import Dict, List, Union from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness Ecu = car.CarParams.Ecu # Steer torque limits @@ -82,53 +82,66 @@ class HyundaiCarInfo(CarInfo): CAR_INFO: Dict[str, Union[HyundaiCarInfo, List[HyundaiCarInfo]]] = { - CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS), - CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c"), - CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-22", video_link="https://youtu.be/_EdYQtV52-c"), - CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS), - CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19"), - CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", "SCC + LFA"), - CAR.IONIQ_EV_LTD: HyundaiCarInfo("Hyundai Ioniq Electric 2019"), - CAR.IONIQ_EV_2020: HyundaiCarInfo("Hyundai Ioniq Electric 2020"), - CAR.IONIQ_PHEV_2019: HyundaiCarInfo("Hyundai Ioniq Plug-in Hybrid 2019", "SCC + LKAS"), - CAR.IONIQ_PHEV: HyundaiCarInfo("Hyundai Ioniq Plug-in Hybrid 2020-21"), - CAR.KONA: HyundaiCarInfo("Hyundai Kona 2020"), - CAR.KONA_EV: HyundaiCarInfo("Hyundai Kona Electric 2018-21"), - CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020"), - CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All"), - CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All"), - CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All"), - CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022", "All"), - CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-22", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw"), - CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19"), - CAR.TUCSON_DIESEL_2019: HyundaiCarInfo("Hyundai Tucson Diesel 2019", "SCC + LKAS"), + CAR.ELANTRA: HyundaiCarInfo("Hyundai Elantra 2017-19", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_b), + CAR.ELANTRA_2021: HyundaiCarInfo("Hyundai Elantra 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), + CAR.ELANTRA_HEV_2021: HyundaiCarInfo("Hyundai Elantra Hybrid 2021-22", video_link="https://youtu.be/_EdYQtV52-c", harness=Harness.hyundai_k), + CAR.HYUNDAI_GENESIS: HyundaiCarInfo("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, harness=Harness.hyundai_j), + CAR.IONIQ: HyundaiCarInfo("Hyundai Ioniq Hybrid 2017-19", harness=Harness.hyundai_c), + CAR.IONIQ_HEV_2022: HyundaiCarInfo("Hyundai Ioniq Hybrid 2020-22", "SCC + LFA", harness=Harness.hyundai_h), + CAR.IONIQ_EV_LTD: HyundaiCarInfo("Hyundai Ioniq Electric 2019", harness=Harness.hyundai_c), + CAR.IONIQ_EV_2020: HyundaiCarInfo("Hyundai Ioniq Electric 2020", harness=Harness.hyundai_h), + CAR.IONIQ_PHEV_2019: HyundaiCarInfo("Hyundai Ioniq Plug-in Hybrid 2019", harness=Harness.hyundai_c), + CAR.IONIQ_PHEV: HyundaiCarInfo("Hyundai Ioniq Plug-in Hybrid 2020-21", harness=Harness.hyundai_h), + CAR.KONA: HyundaiCarInfo("Hyundai Kona 2020", harness=Harness.hyundai_b), + CAR.KONA_EV: HyundaiCarInfo("Hyundai Kona Electric 2018-21", harness=Harness.hyundai_g), + CAR.KONA_HEV: HyundaiCarInfo("Hyundai Kona Hybrid 2020", harness=Harness.hyundai_i), + CAR.SANTA_FE: HyundaiCarInfo("Hyundai Santa Fe 2019-20", "All", harness=Harness.hyundai_d), + CAR.SANTA_FE_2022: HyundaiCarInfo("Hyundai Santa Fe 2021-22", "All", harness=Harness.hyundai_l), + CAR.SANTA_FE_HEV_2022: HyundaiCarInfo("Hyundai Santa Fe Hybrid 2022", "All", harness=Harness.hyundai_l), + CAR.SANTA_FE_PHEV_2022: HyundaiCarInfo("Hyundai Santa Fe Plug-in Hybrid 2022", "All", harness=Harness.hyundai_l), + CAR.SONATA: HyundaiCarInfo("Hyundai Sonata 2020-22", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", harness=Harness.hyundai_a), + CAR.SONATA_LF: HyundaiCarInfo("Hyundai Sonata 2018-19", harness=Harness.hyundai_e), + CAR.TUCSON_DIESEL_2019: HyundaiCarInfo("Hyundai Tucson Diesel 2019", harness=Harness.hyundai_l), CAR.PALISADE: [ - HyundaiCarInfo("Hyundai Palisade 2020-21", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456"), - HyundaiCarInfo("Kia Telluride 2020"), + HyundaiCarInfo("Hyundai Palisade 2020-21", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", harness=Harness.hyundai_h), + HyundaiCarInfo("Kia Telluride 2020", harness=Harness.hyundai_h), ], - CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS), - CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All"), + CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, harness=Harness.hyundai_e), + CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", harness=Harness.hyundai_a), # Kia - CAR.KIA_FORTE: HyundaiCarInfo("Kia Forte 2018-21"), - CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "SCC + LFA"), - CAR.KIA_NIRO_EV: HyundaiCarInfo("Kia Niro Electric 2019-22", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo"), - CAR.KIA_NIRO_HEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2019", min_enable_speed=10. * CV.MPH_TO_MS), - CAR.KIA_NIRO_HEV_2021: HyundaiCarInfo("Kia Niro Hybrid 2021-22"), + CAR.KIA_FORTE: [ + HyundaiCarInfo("Kia Forte 2018", harness=Harness.hyundai_b), + HyundaiCarInfo("Kia Forte 2019-21", harness=Harness.hyundai_g), + ], + CAR.KIA_K5_2021: HyundaiCarInfo("Kia K5 2021-22", "SCC + LFA", harness=Harness.hyundai_a), + CAR.KIA_NIRO_EV: [ + HyundaiCarInfo("Kia Niro Electric 2019-20", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_f), + HyundaiCarInfo("Kia Niro Electric 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Niro Electric 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", harness=Harness.hyundai_h), + ], + CAR.KIA_NIRO_HEV: HyundaiCarInfo("Kia Niro Plug-in Hybrid 2019", min_enable_speed=10. * CV.MPH_TO_MS, harness=Harness.hyundai_c), + CAR.KIA_NIRO_HEV_2021: [ + HyundaiCarInfo("Kia Niro Hybrid 2021", harness=Harness.hyundai_f), # TODO: could be hyundai_d, verify + HyundaiCarInfo("Kia Niro Hybrid 2022", harness=Harness.hyundai_h), + ], CAR.KIA_OPTIMA: [ - HyundaiCarInfo("Kia Optima 2017", min_steer_speed=32. * CV.MPH_TO_MS), - HyundaiCarInfo("Kia Optima 2019"), + HyundaiCarInfo("Kia Optima 2017", min_steer_speed=32. * CV.MPH_TO_MS, harness=Harness.hyundai_b), + HyundaiCarInfo("Kia Optima 2019", harness=Harness.hyundai_g), + ], + CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021", harness=Harness.hyundai_a), + CAR.KIA_SORENTO: [ + HyundaiCarInfo("Kia Sorento 2018", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_c), + HyundaiCarInfo("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", harness=Harness.hyundai_e), ], - CAR.KIA_SELTOS: HyundaiCarInfo("Kia Seltos 2021"), - CAR.KIA_SORENTO: HyundaiCarInfo("Kia Sorento 2018-19", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8"), - CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0"), - CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019"), + CAR.KIA_STINGER: HyundaiCarInfo("Kia Stinger 2018", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", harness=Harness.hyundai_c), + CAR.KIA_CEED: HyundaiCarInfo("Kia Ceed 2019", harness=Harness.hyundai_e), # Genesis - CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018", "All"), - CAR.GENESIS_G70_2020: HyundaiCarInfo("Genesis G70 2020", "All"), - CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2018", "All"), - CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2018", "All"), + CAR.GENESIS_G70: HyundaiCarInfo("Genesis G70 2018", "All", harness=Harness.hyundai_f), + CAR.GENESIS_G70_2020: HyundaiCarInfo("Genesis G70 2020", "All", harness=Harness.hyundai_f), + CAR.GENESIS_G80: HyundaiCarInfo("Genesis G80 2018", "All", harness=Harness.hyundai_h), + CAR.GENESIS_G90: HyundaiCarInfo("Genesis G90 2018", "All", harness=Harness.hyundai_c), } class Buttons: diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index a196b82a9e..5c80303dbc 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -1,8 +1,9 @@ from dataclasses import dataclass +from enum import Enum from typing import Dict, List, Union from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness from cereal import car Ecu = car.CarParams.Ecu @@ -31,6 +32,7 @@ class CAR: @dataclass class MazdaCarInfo(CarInfo): package: str = "All" + harness: Enum = Harness.mazda CAR_INFO: Dict[str, Union[MazdaCarInfo, List[MazdaCarInfo]]] = { diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 51ee7b5286..7c025ad6d6 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -1,8 +1,9 @@ from dataclasses import dataclass from typing import Dict, List, Union +from enum import Enum from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness from cereal import car Ecu = car.CarParams.Ecu @@ -28,13 +29,14 @@ class CAR: @dataclass class NissanCarInfo(CarInfo): package: str = "ProPILOT" + harness: Enum = Harness.nissan_a CAR_INFO: Dict[str, Union[NissanCarInfo, List[NissanCarInfo]]] = { CAR.XTRAIL: NissanCarInfo("Nissan X-Trail 2017"), CAR.LEAF: NissanCarInfo("Nissan Leaf 2018-22"), CAR.ROGUE: NissanCarInfo("Nissan Rogue 2018-20"), - CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20"), + CAR.ALTIMA: NissanCarInfo("Nissan Altima 2019-20", harness=Harness.nissan_b), } FINGERPRINTS = { diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 2aca2af576..6e81fcb1b3 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -1,11 +1,14 @@ from dataclasses import dataclass +from enum import Enum from typing import Dict, List, Union from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarInfo +from selfdrive.car.docs_definitions import CarInfo, Harness from cereal import car + Ecu = car.CarParams.Ecu + class CarControllerParams: def __init__(self, CP): if CP.carFingerprint == CAR.IMPREZA_2020: @@ -34,6 +37,7 @@ class CAR: @dataclass class SubaruCarInfo(CarInfo): package: str = "EyeSight" + harness: Enum = Harness.subaru CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index e3cb0b091b..e047396c7b 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -6,7 +6,7 @@ from typing import Dict, List, Union from cereal import car from common.conversions import Conversions as CV from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Star +from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness, Star Ecu = car.CarParams.Ecu MIN_ACC_SPEED = 19. * CV.MPH_TO_MS @@ -100,6 +100,7 @@ class Footnote(Enum): class ToyotaCarInfo(CarInfo): package: str = "All" good_torque: bool = True + harness: Enum = Harness.toyota CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 3555b29082..abba70fbba 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -5,13 +5,14 @@ from typing import Dict, List, Union from cereal import car from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column +from selfdrive.car.docs_definitions import CarFootnote, CarInfo, Column, Harness Ecu = car.CarParams.Ecu NetworkLocation = car.CarParams.NetworkLocation TransmissionType = car.CarParams.TransmissionType GearShifter = car.CarState.GearShifter + class CarControllerParams: HCA_STEP = 2 # HCA_01 message frequency 50Hz LDW_STEP = 10 # LDW_02 message frequency 10Hz @@ -30,13 +31,16 @@ class CarControllerParams: STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily STEER_DRIVER_FACTOR = 1 # from dbc + class CANBUS: pt = 0 cam = 2 + class DBC_FILES: mqb = "vw_mqb_2010" # Used for all cars with MQB-style CAN messaging + DBC = defaultdict(lambda: dbc_dict(DBC_FILES.mqb, None)) # type: Dict[str, Dict[str, str]] BUTTON_STATES = { @@ -60,6 +64,7 @@ MQB_LDW_MESSAGES = { "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward } + # Check the 7th and 8th characters of the VIN before adding a new CAR. If the # chassis code is already listed below, don't add a new CAR, just add to the # FW_VERSIONS for that existing CAR. @@ -110,11 +115,12 @@ class Footnote(Enum): class VWCarInfo(CarInfo): package: str = "Driver Assistance" good_torque: bool = True + harness: Enum = Harness.vw CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { - CAR.ARTEON_MK1: VWCarInfo("Volkswagen Arteon 2018, 2021", footnotes=[Footnote.VW_HARNESS]), - CAR.ATLAS_MK1: VWCarInfo("Volkswagen Atlas 2018-19, 2022", footnotes=[Footnote.VW_HARNESS]), + CAR.ARTEON_MK1: VWCarInfo("Volkswagen Arteon 2018, 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + CAR.ATLAS_MK1: VWCarInfo("Volkswagen Atlas 2018-19, 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.GOLF_MK7: [ VWCarInfo("Volkswagen e-Golf 2014, 2018-20"), VWCarInfo("Volkswagen Golf 2015-20"), @@ -131,15 +137,15 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { ], CAR.PASSAT_MK8: VWCarInfo("Volkswagen Passat 2016-18", footnotes=[Footnote.PASSAT]), CAR.POLO_MK6: VWCarInfo("Volkswagen Polo 2020"), - CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS]), - CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS]), - CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS]), + CAR.TAOS_MK1: VWCarInfo("Volkswagen Taos 2022", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + CAR.TCROSS_MK1: VWCarInfo("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + CAR.TIGUAN_MK2: VWCarInfo("Volkswagen Tiguan 2019-22", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.TOURAN_MK2: VWCarInfo("Volkswagen Touran 2017"), CAR.TRANSPORTER_T61: [ - VWCarInfo("Volkswagen Caravelle 2020", footnotes=[Footnote.VW_HARNESS]), - VWCarInfo("Volkswagen California 2021", footnotes=[Footnote.VW_HARNESS]), + VWCarInfo("Volkswagen Caravelle 2020", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), + VWCarInfo("Volkswagen California 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), ], - CAR.TROC_MK1: VWCarInfo("Volkswagen T-Roc 2021", footnotes=[Footnote.VW_HARNESS]), + CAR.TROC_MK1: VWCarInfo("Volkswagen T-Roc 2021", footnotes=[Footnote.VW_HARNESS], harness=Harness.j533), CAR.AUDI_A3_MK3: [ VWCarInfo("Audi A3 2014-19", "ACC + Lane Assist"), VWCarInfo("Audi A3 Sportback e-tron 2017-18", "ACC + Lane Assist"), From 3f5afa158a96a0855b37c1a4f55a99949fe20444 Mon Sep 17 00:00:00 2001 From: cydia2020 <12470297+cydia2020@users.noreply.github.com> Date: Thu, 12 May 2022 14:02:47 +1000 Subject: [PATCH 084/391] Toyota: correct weight for the Prius V (#24499) * correct weight for the Prius V https://www.toyotacertified.com/content/dam/tcuv/sections/brochures/en/prius-v/2017_priusv_ebrochure.pdf * Remove comment Co-authored-by: Adeeb Shihadeh * Extra whitespace Co-authored-by: Adeeb Shihadeh --- selfdrive/car/toyota/interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 559307ef2d..cecb0aa3e8 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -46,7 +46,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.78 ret.steerRatio = 17.4 tire_stiffness_factor = 0.5533 - ret.mass = 4387. * CV.LB_TO_KG + STD_CARGO_KG + ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.TORQUE, MAX_LAT_ACCEL=1.8, FRICTION=0.06) elif candidate in (CAR.RAV4, CAR.RAV4H): From 75f21492671ad34949061e57760b360e93e440f9 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 12 May 2022 12:43:07 +0200 Subject: [PATCH 085/391] encoderd: update deprecated ffmpeg functions (#24501) --- selfdrive/loggerd/encoder/ffmpeg_encoder.cc | 2 +- selfdrive/loggerd/encoder/video_writer.cc | 9 ++------- selfdrive/loggerd/encoder/video_writer.h | 1 + 3 files changed, 4 insertions(+), 8 deletions(-) diff --git a/selfdrive/loggerd/encoder/ffmpeg_encoder.cc b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc index 139ffe3f24..7011f43a23 100644 --- a/selfdrive/loggerd/encoder/ffmpeg_encoder.cc +++ b/selfdrive/loggerd/encoder/ffmpeg_encoder.cc @@ -47,7 +47,7 @@ FfmpegEncoder::~FfmpegEncoder() { } void FfmpegEncoder::encoder_open(const char* path) { - AVCodec *codec = avcodec_find_encoder(AV_CODEC_ID_FFVHUFF); + const AVCodec *codec = avcodec_find_encoder(AV_CODEC_ID_FFVHUFF); this->codec_ctx = avcodec_alloc_context3(codec); assert(this->codec_ctx); diff --git a/selfdrive/loggerd/encoder/video_writer.cc b/selfdrive/loggerd/encoder/video_writer.cc index c02592583a..4eb66606c6 100644 --- a/selfdrive/loggerd/encoder/video_writer.cc +++ b/selfdrive/loggerd/encoder/video_writer.cc @@ -1,5 +1,3 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - #include #include @@ -23,11 +21,8 @@ VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, assert(this->ofmt_ctx); // set codec correctly. needed? - av_register_all(); - - AVCodec *avcodec = NULL; assert(codec != cereal::EncodeIndex::Type::FULL_H_E_V_C); - avcodec = avcodec_find_encoder(raw ? AV_CODEC_ID_FFVHUFF : AV_CODEC_ID_H264); + const AVCodec *avcodec = avcodec_find_encoder(raw ? AV_CODEC_ID_FFVHUFF : AV_CODEC_ID_H264); assert(avcodec); this->codec_ctx = avcodec_alloc_context3(avcodec); @@ -95,7 +90,7 @@ void VideoWriter::write(uint8_t *data, int len, long long timestamp, bool codecc int err = av_interleaved_write_frame(ofmt_ctx, &pkt); if (err < 0) { LOGW("ts encoder write issue"); } - av_free_packet(&pkt); + av_packet_unref(&pkt); } } } diff --git a/selfdrive/loggerd/encoder/video_writer.h b/selfdrive/loggerd/encoder/video_writer.h index 217964e0ef..01a243904c 100644 --- a/selfdrive/loggerd/encoder/video_writer.h +++ b/selfdrive/loggerd/encoder/video_writer.h @@ -4,6 +4,7 @@ extern "C" { #include +#include } #include "cereal/messaging/messaging.h" From fab611c2ce0ccd51b3627e6287e80af00381cf31 Mon Sep 17 00:00:00 2001 From: Willem Melching Date: Thu, 12 May 2022 12:43:20 +0200 Subject: [PATCH 086/391] Pipfile: remove carla for MacOS installs (#24502) * no carla for mac * lock --- Pipfile | 2 +- Pipfile.lock | 33 +++++++++++++++++---------------- 2 files changed, 18 insertions(+), 17 deletions(-) diff --git a/Pipfile b/Pipfile index af3e02f54a..1f0f91dbeb 100644 --- a/Pipfile +++ b/Pipfile @@ -38,7 +38,7 @@ breathe = "*" subprocess32 = "*" tenacity = "*" mpld3 = "*" -carla = "==0.9.12" +carla = {version = "==0.9.12", markers="platform_system != 'Darwin'"} [packages] atomicwrites = "*" diff --git a/Pipfile.lock b/Pipfile.lock index d7372d3ca3..3f4bd1f4fd 100644 --- a/Pipfile.lock +++ b/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "19a7b58f24cd7542ccb9fd386c7716d77fff3c1f87de496f3f42753cf34a5dde" + "sha256": "72117588efb763049752818a64ea7b13448e2ec7e396e8dd4bd7f066622c5314" }, "pipfile-spec": 6, "requires": { @@ -366,7 +366,7 @@ "sha256:6f62d78e2f89b4500b080fe3a81690850cd254227f27f75c3a0c491a1f351ba7", "sha256:e8443a5e7a020e9d7f97f1d7d9cd17c88bcb3bc7e218bf9cf5095fe550be2951" ], - "markers": "python_version < '4.0' and python_full_version >= '3.6.1'", + "markers": "python_version < '4' and python_full_version >= '3.6.1'", "version": "==5.10.1" }, "itsdangerous": { @@ -988,11 +988,11 @@ }, "sentry-sdk": { "hashes": [ - "sha256:6c01d9d0b65935fd275adc120194737d1df317dce811e642cbf0394d0d37a007", - "sha256:c17179183cac614e900cbd048dab03f49a48e2820182ec686c25e7ce46f8548f" + "sha256:259535ba66933eacf85ab46524188c84dcb4c39f40348455ce15e2c0aca68863", + "sha256:778b53f0a6c83b1ee43d3b7886318ba86d975e686cb2c7906ccc35b334360be1" ], "index": "pypi", - "version": "==1.5.11" + "version": "==1.5.12" }, "setproctitle": { "hashes": [ @@ -1073,11 +1073,11 @@ }, "setuptools": { "hashes": [ - "sha256:26ead7d1f93efc0f8c804d9fafafbe4a44b179580a7105754b245155f9af05a8", - "sha256:47c7b0c0f8fc10eec4cf1e71c6fdadf8decaa74ffa087e68cd1c20db7ad6a592" + "sha256:5534570b9980fc650d45c62877ff603c7aaaf24893371708736cc016bd221c3c", + "sha256:ca6ba73b7fd5f734ae70ece8c4c1f7062b07f3352f6428f6277e27c8f5c64237" ], "markers": "python_version >= '3.7'", - "version": "==62.1.0" + "version": "==62.2.0" }, "six": { "hashes": [ @@ -1132,7 +1132,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.2.0" }, "urllib3": { @@ -1327,6 +1327,7 @@ "sha256:dd392a267e14b785a8f65dafef86e05a92201253e9fb4a01e1e262834f20bed2" ], "index": "pypi", + "markers": "platform_system != 'Darwin'", "version": "==0.9.12" }, "certifi": { @@ -1597,11 +1598,11 @@ }, "hypothesis": { "hashes": [ - "sha256:37ca37f61939d0a92c18b5e17ab8088dccc5fc077c913d6619bbe1d233dfca1e", - "sha256:c671b3801527f3a8189314d9385418a67d4c7ab1b3330a3ff8b267d0d4599b3d" + "sha256:022c269158a2db28c40a005fc477f18a1395025dd8b09ce394e49cd0f36c550a", + "sha256:8d65fcd14634b08f5b2237f66b9cb188df84a81a5cffd3e9748de24baf0fa535" ], "index": "pypi", - "version": "==6.46.2" + "version": "==6.46.3" }, "identify": { "hashes": [ @@ -2143,11 +2144,11 @@ }, "pyparsing": { "hashes": [ - "sha256:7bf433498c016c4314268d95df76c81b842a4cb2b276fa3312cfb1e1d85f6954", - "sha256:ef7b523f6356f763771559412c0d7134753f037822dad1b16945b7b846f7ad06" + "sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb", + "sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc" ], "markers": "python_full_version >= '3.6.8'", - "version": "==3.0.8" + "version": "==3.0.9" }, "pyprof2calltree": { "hashes": [ @@ -2409,7 +2410,7 @@ "sha256:6657594ee297170d19f67d55c05852a874e7eb634f4f753dbd667855e07c1708", "sha256:f1c24655a0da0d1b67f07e17a5e6b2a105894e6824b92096378bb3668ef02376" ], - "markers": "python_version >= '3.7'", + "markers": "python_version < '3.10'", "version": "==4.2.0" }, "urllib3": { From e84d073233404e3375fc3708c0da079c88c012e5 Mon Sep 17 00:00:00 2001 From: Mark Murnane Date: Thu, 12 May 2022 07:40:05 -0400 Subject: [PATCH 087/391] Add gamepad support for body (#24415) This MR adds basic gamepad support to the joystick web client. The mappings appear to be consistent between a few controllers I tried, so I think inverting both axes is the optimal mapping. --- tools/joystick/web.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/tools/joystick/web.py b/tools/joystick/web.py index 5db48eea24..5cba4e938d 100755 --- a/tools/joystick/web.py +++ b/tools/joystick/web.py @@ -16,11 +16,24 @@ index = """