From 7119a98414f10876c4b26b58f6f1c639c04f9762 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] 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 old-commit-hash: 0baa4c3e2ad9ee6f8daba8267db44c2cd44caa62 --- 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 | 3 - third_party/openmax/include/OMX_Component.h | 3 - third_party/openmax/include/OMX_ContentPipe.h | 3 - third_party/openmax/include/OMX_Core.h | 3 - third_party/openmax/include/OMX_CoreExt.h | 3 - third_party/openmax/include/OMX_IVCommon.h | 3 - third_party/openmax/include/OMX_Image.h | 3 - third_party/openmax/include/OMX_Index.h | 3 - third_party/openmax/include/OMX_IndexExt.h | 3 - third_party/openmax/include/OMX_Other.h | 3 - third_party/openmax/include/OMX_QCOMExtns.h | 3 - .../include/OMX_Skype_VideoExtensions.h | 3 - third_party/openmax/include/OMX_Types.h | 3 - third_party/openmax/include/OMX_Video.h | 3 - third_party/openmax/include/OMX_VideoExt.h | 3 - tools/camerastream/compressed_vipc.py | 26 +- 38 files changed, 2445 insertions(+), 709 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 16297a7d18..0000000000 --- a/third_party/openmax/include/OMX_Audio.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a79a84bd1d498a6bb4f2be0c72bfc31e9549509953027ed06daed495f8603200 -size 77117 diff --git a/third_party/openmax/include/OMX_Component.h b/third_party/openmax/include/OMX_Component.h deleted file mode 100644 index ab10ce9fe5..0000000000 --- a/third_party/openmax/include/OMX_Component.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1511c182af584c7605682d1b9cba4949cdb99169a78730a677ea1a9e985f778b -size 23869 diff --git a/third_party/openmax/include/OMX_ContentPipe.h b/third_party/openmax/include/OMX_ContentPipe.h deleted file mode 100644 index 476a531cf9..0000000000 --- a/third_party/openmax/include/OMX_ContentPipe.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:3d83ce4f1313757b4db838a9122d99048176e7edeb104e52b90ff9d52b8955ec -size 9223 diff --git a/third_party/openmax/include/OMX_Core.h b/third_party/openmax/include/OMX_Core.h deleted file mode 100644 index de90bb68f1..0000000000 --- a/third_party/openmax/include/OMX_Core.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:759bccdbaa1c6afa189e5a528dd75602763c4a77ff14b581e9178c387342dff1 -size 70034 diff --git a/third_party/openmax/include/OMX_CoreExt.h b/third_party/openmax/include/OMX_CoreExt.h deleted file mode 100644 index 6c2a64b6ed..0000000000 --- a/third_party/openmax/include/OMX_CoreExt.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:cd5af1232e30e239bf82f42322ac623e116272a2ba7968a0050a7602c417790e -size 2593 diff --git a/third_party/openmax/include/OMX_IVCommon.h b/third_party/openmax/include/OMX_IVCommon.h deleted file mode 100644 index 90f7c313c2..0000000000 --- a/third_party/openmax/include/OMX_IVCommon.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:242b6d449fadd52df0ed1935e3803ac8e12b48e19a466968a27901fa52714fd4 -size 33141 diff --git a/third_party/openmax/include/OMX_Image.h b/third_party/openmax/include/OMX_Image.h deleted file mode 100644 index 4c1bffa7e6..0000000000 --- a/third_party/openmax/include/OMX_Image.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7a3f1a490953a4453347fb2c99dc4d9dcc9f3418202942aef6aaeb5e7b65dde7 -size 13267 diff --git a/third_party/openmax/include/OMX_Index.h b/third_party/openmax/include/OMX_Index.h deleted file mode 100644 index 48b2b359e7..0000000000 --- a/third_party/openmax/include/OMX_Index.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f4e3deb7606f867f327e8d6f2ef6345187db712fedd43e9f1b34b37b923485c4 -size 17977 diff --git a/third_party/openmax/include/OMX_IndexExt.h b/third_party/openmax/include/OMX_IndexExt.h deleted file mode 100644 index 26016e06ef..0000000000 --- a/third_party/openmax/include/OMX_IndexExt.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:fa8479b1ffa0a9357e32a162052901c6277fcc1f78b4c7f7503f145e4990f5bc -size 4239 diff --git a/third_party/openmax/include/OMX_Other.h b/third_party/openmax/include/OMX_Other.h deleted file mode 100644 index c76b1342db..0000000000 --- a/third_party/openmax/include/OMX_Other.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a20c53c71ba440d6f1293625a79377dbc2f688c6ec7e81560790acdc134191e5 -size 17932 diff --git a/third_party/openmax/include/OMX_QCOMExtns.h b/third_party/openmax/include/OMX_QCOMExtns.h deleted file mode 100644 index f12088fde4..0000000000 --- a/third_party/openmax/include/OMX_QCOMExtns.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a1d61fb5649544c473a98bf955b4bea2e51ea7a10841732640b27ac2e16e7280 -size 67453 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 1a925614b9..0000000000 --- a/third_party/openmax/include/OMX_Skype_VideoExtensions.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:bb0b58976083bf927080d193d896396735171b479bc2efd9ac6d7453284a1c33 -size 4729 diff --git a/third_party/openmax/include/OMX_Types.h b/third_party/openmax/include/OMX_Types.h deleted file mode 100644 index 076f33a0d7..0000000000 --- a/third_party/openmax/include/OMX_Types.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:ff5592a4396b7f1331e39f886429eda3d57eb424ce1aea0ffe7d86c15236bad5 -size 12542 diff --git a/third_party/openmax/include/OMX_Video.h b/third_party/openmax/include/OMX_Video.h deleted file mode 100644 index bce363ebf1..0000000000 --- a/third_party/openmax/include/OMX_Video.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:9e019a14f0204796d40cc20b869ad654ea3a643349a8cc591bd5178e7090fc8d -size 44945 diff --git a/third_party/openmax/include/OMX_VideoExt.h b/third_party/openmax/include/OMX_VideoExt.h deleted file mode 100644 index 2dd7b63770..0000000000 --- a/third_party/openmax/include/OMX_VideoExt.h +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e685e54fc7058a951b91339df4622f6cfdd42f9e0c7811b38bb97b412f84803a -size 5628 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()