diff --git a/SConstruct b/SConstruct index 48a5e0e2af..520716859a 100644 --- a/SConstruct +++ b/SConstruct @@ -184,7 +184,6 @@ env = Environment( "#third_party/acados/include/hpipm/include", "#third_party/catch2/include", "#third_party/libyuv/include", - "#third_party/openmax/include", "#third_party/json11", "#third_party/curl/include", "#third_party/libgralloc/include", diff --git a/cereal b/cereal index a057aed167..aea23111ee 160000 --- a/cereal +++ b/cereal @@ -1 +1 @@ -Subproject commit a057aed16747d0e414145d83d4861c50315781ad +Subproject commit aea23111ee0a08efb549d1d318405b9af8f456d9 diff --git a/release/files_common b/release/files_common index 1592fcf8ad..c44f10229e 100644 --- a/release/files_common +++ b/release/files_common @@ -299,19 +299,21 @@ selfdrive/proclogd/proclog.h selfdrive/loggerd/SConscript selfdrive/loggerd/encoder.h -selfdrive/loggerd/omx_encoder.cc -selfdrive/loggerd/omx_encoder.h +selfdrive/loggerd/v4l_encoder.cc +selfdrive/loggerd/v4l_encoder.h selfdrive/loggerd/video_writer.cc selfdrive/loggerd/video_writer.h +selfdrive/loggerd/remote_encoder.cc +selfdrive/loggerd/remote_encoder.h selfdrive/loggerd/logger.cc selfdrive/loggerd/logger.h selfdrive/loggerd/loggerd.cc selfdrive/loggerd/loggerd.h +selfdrive/loggerd/encoderd.cc selfdrive/loggerd/main.cc selfdrive/loggerd/bootlog.cc selfdrive/loggerd/raw_logger.cc selfdrive/loggerd/raw_logger.h -selfdrive/loggerd/include/msm_media_info.h selfdrive/loggerd/__init__.py selfdrive/loggerd/config.py @@ -444,7 +446,6 @@ third_party/SConscript third_party/linux/** third_party/opencl/** -third_party/openmax/** third_party/json11/json11.cpp third_party/json11/json11.hpp diff --git a/selfdrive/loggerd/.gitignore b/selfdrive/loggerd/.gitignore index 4a8755b956..6437be5e38 100644 --- a/selfdrive/loggerd/.gitignore +++ b/selfdrive/loggerd/.gitignore @@ -1,2 +1,3 @@ loggerd +encoderd tests/test_logger diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 92cc37a5fb..1efa99298b 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -1,15 +1,13 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon') - +Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc') libs = [common, cereal, messaging, visionipc, 'zmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'bz2', 'OpenCL', 'pthread'] -src = ['logger.cc', 'loggerd.cc', 'video_writer.cc'] +src = ['logger.cc', 'loggerd.cc', 'video_writer.cc', 'remote_encoder.cc'] if arch == "larch64": - src += ['omx_encoder.cc'] - libs += ['OmxCore', 'gsl', 'CB'] + gpucommon + src += ['v4l_encoder.cc'] else: src += ['raw_logger.cc'] @@ -22,6 +20,8 @@ logger_lib = env.Library('logger', src) libs.insert(0, logger_lib) env.Program('loggerd', ['main.cc'], LIBS=libs) +if arch == "larch64": + env.Program('encoderd', ['encoderd.cc'], LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): diff --git a/selfdrive/loggerd/encoder.h b/selfdrive/loggerd/encoder.h index 3d9f957d9f..0a5afa007c 100644 --- a/selfdrive/loggerd/encoder.h +++ b/selfdrive/loggerd/encoder.h @@ -1,13 +1,13 @@ #pragma once #include -#include "selfdrive/loggerd/loggerd.h" +#include "cereal/visionipc/visionipc.h" class VideoEncoder { public: virtual ~VideoEncoder() {} virtual int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) = 0; + int in_width, int in_height, VisionIpcBufExtra *extra) = 0; virtual void encoder_open(const char* path) = 0; virtual void encoder_close() = 0; }; diff --git a/selfdrive/loggerd/encoderd.cc b/selfdrive/loggerd/encoderd.cc new file mode 100644 index 0000000000..ac57d3eea5 --- /dev/null +++ b/selfdrive/loggerd/encoderd.cc @@ -0,0 +1,145 @@ +#include "selfdrive/loggerd/loggerd.h" + +ExitHandler do_exit; + +struct EncoderdState { + int max_waiting = 0; + + // Sync logic for startup + std::atomic encoders_ready = 0; + std::atomic start_frame_id = 0; + bool camera_ready[WideRoadCam + 1] = {}; + bool camera_synced[WideRoadCam + 1] = {}; +}; + +// Handle initial encoder syncing by waiting for all encoders to reach the same frame id +bool sync_encoders(EncoderdState *s, CameraType cam_type, uint32_t frame_id) { + if (s->camera_synced[cam_type]) return true; + + if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { + // add a small margin to the start frame id in case one of the encoders already dropped the next frame + update_max_atomic(s->start_frame_id, frame_id + 2); + if (std::exchange(s->camera_ready[cam_type], true) == false) { + ++s->encoders_ready; + LOGD("camera %d encoder ready", cam_type); + } + return false; + } else { + if (s->max_waiting == 1) update_max_atomic(s->start_frame_id, frame_id); + bool synced = frame_id >= s->start_frame_id; + s->camera_synced[cam_type] = synced; + if (!synced) LOGD("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); + return synced; + } +} + + +void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { + util::set_thread_name(cam_info.filename); + + std::vector encoders; + VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); + + int cur_seg = 0; + while (!do_exit) { + if (!vipc_client.connect(false)) { + util::sleep_for(5); + continue; + } + + // init encoders + if (encoders.empty()) { + VisionBuf buf_info = vipc_client.buffers[0]; + LOGD("encoder init %dx%d", buf_info.width, buf_info.height); + + // main encoder + encoders.push_back(new Encoder(cam_info.filename, cam_info.type, buf_info.width, buf_info.height, + cam_info.fps, cam_info.bitrate, cam_info.is_h265, + buf_info.width, buf_info.height, false)); + // qcamera encoder + if (cam_info.has_qcamera) { + encoders.push_back(new Encoder(qcam_info.filename, cam_info.type, buf_info.width, buf_info.height, + qcam_info.fps, qcam_info.bitrate, qcam_info.is_h265, + qcam_info.frame_width, qcam_info.frame_height, false)); + } + } + + for (int i = 0; i < encoders.size(); ++i) { + encoders[i]->encoder_open(NULL); + } + + bool lagging = false; + while (!do_exit) { + VisionIpcBufExtra extra; + VisionBuf* buf = vipc_client.recv(&extra); + if (buf == nullptr) continue; + + // detect loop around and drop the frames + if (buf->get_frame_id() != extra.frame_id) { + if (!lagging) { + LOGE("encoder %s lag buffer id: %d extra id: %d", cam_info.filename, buf->get_frame_id(), extra.frame_id); + lagging = true; + } + continue; + } + lagging = false; + + if (cam_info.trigger_rotate) { + if (!sync_encoders(s, cam_info.type, extra.frame_id)) { + continue; + } + if (do_exit) break; + } + + // encode a frame + for (int i = 0; i < encoders.size(); ++i) { + int out_id = encoders[i]->encode_frame(buf->y, buf->u, buf->v, + buf->width, buf->height, &extra); + + if (out_id == -1) { + LOGE("Failed to encode frame. frame_id: %d", extra.frame_id); + } + } + + const int frames_per_seg = SEGMENT_LENGTH * MAIN_FPS; + if (cur_seg >= 0 && extra.frame_id >= ((cur_seg + 1) * frames_per_seg) + s->start_frame_id) { + for (auto &e : encoders) { + e->encoder_close(); + e->encoder_open(NULL); + } + ++cur_seg; + } + } + } + + LOG("encoder destroy"); + for(auto &e : encoders) { + e->encoder_close(); + delete e; + } +} + +void encoderd_thread() { + EncoderdState s; + + std::vector encoder_threads; + for (const auto &cam : cameras_logged) { + if (cam.enable) { + encoder_threads.push_back(std::thread(encoder_thread, &s, cam)); + if (cam.trigger_rotate) s.max_waiting++; + } + } + for (auto &t : encoder_threads) t.join(); +} + +int main() { + if (Hardware::TICI()) { + int ret; + ret = util::set_realtime_priority(52); + assert(ret == 0); + ret = util::set_core_affinity({7}); + assert(ret == 0); + } + encoderd_thread(); + return 0; +} diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index a2c2b45a2b..e6bc4fcfa5 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -1,4 +1,6 @@ #include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/remote_encoder.h" +bool USE_REMOTE_ENCODER = false; ExitHandler do_exit; @@ -107,7 +109,7 @@ void encoder_thread(LoggerdState *s, const LogCameraInfo &cam_info) { // encode a frame for (int i = 0; i < encoders.size(); ++i) { int out_id = encoders[i]->encode_frame(buf->y, buf->u, buf->v, - buf->width, buf->height, extra.timestamp_eof); + buf->width, buf->height, &extra); if (out_id == -1) { LOGE("Failed to encode frame. frame_id: %d encode_id: %d", extra.frame_id, encode_idx); @@ -188,15 +190,18 @@ void loggerd_thread() { typedef struct QlogState { std::string name; int counter, freq; + bool encoder; } QlogState; std::unordered_map qlog_states; + std::unordered_map remote_encoders; std::unique_ptr ctx(Context::create()); std::unique_ptr poller(Poller::create()); // subscribe to all socks for (const auto& it : services) { - if (!it.should_log) continue; + const bool encoder = USE_REMOTE_ENCODER & (strcmp(it.name+strlen(it.name)-strlen("EncodeData"), "EncodeData") == 0); + if (!it.should_log && !encoder) continue; LOGD("logging %s (on port %d)", it.name, it.port); SubSocket * sock = SubSocket::create(ctx.get(), it.name); @@ -206,6 +211,7 @@ void loggerd_thread() { .name = it.name, .counter = 0, .freq = it.decimation, + .encoder = encoder, }; } @@ -238,9 +244,14 @@ void loggerd_thread() { Message *msg = nullptr; while (!do_exit && (msg = sock->receive(true))) { const bool in_qlog = qs.freq != -1 && (qs.counter++ % qs.freq == 0); - logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); - bytes_count += msg->getSize(); - delete msg; + + if (qs.encoder) { + bytes_count += handle_encoder_msg(&s, msg, qs.name, remote_encoders[sock]); + } else { + logger_log(&s.logger, (uint8_t *)msg->getData(), msg->getSize(), in_qlog); + bytes_count += msg->getSize(); + delete msg; + } rotate_if_needed(&s); diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index 761ff5507a..ec014649a8 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -25,8 +25,8 @@ #include "selfdrive/loggerd/encoder.h" #include "selfdrive/loggerd/logger.h" #ifdef QCOM2 -#include "selfdrive/loggerd/omx_encoder.h" -#define Encoder OmxEncoder +#include "selfdrive/loggerd/v4l_encoder.h" +#define Encoder V4LEncoder #else #include "selfdrive/loggerd/raw_logger.h" #define Encoder RawLogger @@ -67,6 +67,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = true, .record = true, + .frame_width = 1928, + .frame_height = 1208, }, { .type = DriverCam, @@ -79,6 +81,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = true, .record = Params().getBool("RecordFront"), + .frame_width = 1928, + .frame_height = 1208, }, { .type = WideRoadCam, @@ -91,6 +95,8 @@ const LogCameraInfo cameras_logged[] = { .trigger_rotate = true, .enable = Hardware::TICI(), .record = Hardware::TICI(), + .frame_width = 1928, + .frame_height = 1208, }, }; const LogCameraInfo qcam_info = { @@ -98,6 +104,8 @@ const LogCameraInfo qcam_info = { .fps = MAIN_FPS, .bitrate = 256000, .is_h265 = false, + .enable = true, + .record = true, .frame_width = Hardware::TICI() ? 526 : 480, .frame_height = Hardware::TICI() ? 330 : 360 // keep pixel count the same? }; diff --git a/selfdrive/loggerd/omx_encoder.cc b/selfdrive/loggerd/omx_encoder.cc deleted file mode 100644 index 31e035955a..0000000000 --- a/selfdrive/loggerd/omx_encoder.cc +++ /dev/null @@ -1,547 +0,0 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - -#include "selfdrive/loggerd/omx_encoder.h" -#include "cereal/messaging/messaging.h" - -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include "libyuv.h" - -#include "selfdrive/common/swaglog.h" -#include "selfdrive/common/util.h" -#include "selfdrive/loggerd/include/msm_media_info.h" - -// Check the OMX error code and assert if an error occurred. -#define OMX_CHECK(_expr) \ - do { \ - assert(OMX_ErrorNone == (_expr)); \ - } while (0) - -extern ExitHandler do_exit; - -// ***** OMX callback functions ***** - -void OmxEncoder::wait_for_state(OMX_STATETYPE state_) { - std::unique_lock lk(this->state_lock); - while (this->state != state_) { - this->state_cv.wait(lk); - } -} - -static OMX_CALLBACKTYPE omx_callbacks = { - .EventHandler = OmxEncoder::event_handler, - .EmptyBufferDone = OmxEncoder::empty_buffer_done, - .FillBufferDone = OmxEncoder::fill_buffer_done, -}; - -OMX_ERRORTYPE OmxEncoder::event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data) { - OmxEncoder *e = (OmxEncoder*)app_data; - if (event == OMX_EventCmdComplete) { - assert(data1 == OMX_CommandStateSet); - LOG("set state event 0x%x", data2); - { - std::unique_lock lk(e->state_lock); - e->state = (OMX_STATETYPE)data2; - } - e->state_cv.notify_all(); - } else if (event == OMX_EventError) { - LOGE("OMX error 0x%08x", data1); - } else { - LOGE("OMX unhandled event %d", event); - assert(false); - } - - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->free_in.push(buffer); - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->done_out.push(buffer); - return OMX_ErrorNone; -} - -#define PORT_INDEX_IN 0 -#define PORT_INDEX_OUT 1 - -static const char* omx_color_fomat_name(uint32_t format) __attribute__((unused)); -static const char* omx_color_fomat_name(uint32_t format) { - switch (format) { - case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused"; - case OMX_COLOR_FormatMonochrome: return "OMX_COLOR_FormatMonochrome"; - case OMX_COLOR_Format8bitRGB332: return "OMX_COLOR_Format8bitRGB332"; - case OMX_COLOR_Format12bitRGB444: return "OMX_COLOR_Format12bitRGB444"; - case OMX_COLOR_Format16bitARGB4444: return "OMX_COLOR_Format16bitARGB4444"; - case OMX_COLOR_Format16bitARGB1555: return "OMX_COLOR_Format16bitARGB1555"; - case OMX_COLOR_Format16bitRGB565: return "OMX_COLOR_Format16bitRGB565"; - case OMX_COLOR_Format16bitBGR565: return "OMX_COLOR_Format16bitBGR565"; - case OMX_COLOR_Format18bitRGB666: return "OMX_COLOR_Format18bitRGB666"; - case OMX_COLOR_Format18bitARGB1665: return "OMX_COLOR_Format18bitARGB1665"; - case OMX_COLOR_Format19bitARGB1666: return "OMX_COLOR_Format19bitARGB1666"; - case OMX_COLOR_Format24bitRGB888: return "OMX_COLOR_Format24bitRGB888"; - case OMX_COLOR_Format24bitBGR888: return "OMX_COLOR_Format24bitBGR888"; - case OMX_COLOR_Format24bitARGB1887: return "OMX_COLOR_Format24bitARGB1887"; - case OMX_COLOR_Format25bitARGB1888: return "OMX_COLOR_Format25bitARGB1888"; - case OMX_COLOR_Format32bitBGRA8888: return "OMX_COLOR_Format32bitBGRA8888"; - case OMX_COLOR_Format32bitARGB8888: return "OMX_COLOR_Format32bitARGB8888"; - case OMX_COLOR_FormatYUV411Planar: return "OMX_COLOR_FormatYUV411Planar"; - case OMX_COLOR_FormatYUV411PackedPlanar: return "OMX_COLOR_FormatYUV411PackedPlanar"; - case OMX_COLOR_FormatYUV420Planar: return "OMX_COLOR_FormatYUV420Planar"; - case OMX_COLOR_FormatYUV420PackedPlanar: return "OMX_COLOR_FormatYUV420PackedPlanar"; - case OMX_COLOR_FormatYUV420SemiPlanar: return "OMX_COLOR_FormatYUV420SemiPlanar"; - case OMX_COLOR_FormatYUV422Planar: return "OMX_COLOR_FormatYUV422Planar"; - case OMX_COLOR_FormatYUV422PackedPlanar: return "OMX_COLOR_FormatYUV422PackedPlanar"; - case OMX_COLOR_FormatYUV422SemiPlanar: return "OMX_COLOR_FormatYUV422SemiPlanar"; - case OMX_COLOR_FormatYCbYCr: return "OMX_COLOR_FormatYCbYCr"; - case OMX_COLOR_FormatYCrYCb: return "OMX_COLOR_FormatYCrYCb"; - case OMX_COLOR_FormatCbYCrY: return "OMX_COLOR_FormatCbYCrY"; - case OMX_COLOR_FormatCrYCbY: return "OMX_COLOR_FormatCrYCbY"; - case OMX_COLOR_FormatYUV444Interleaved: return "OMX_COLOR_FormatYUV444Interleaved"; - case OMX_COLOR_FormatRawBayer8bit: return "OMX_COLOR_FormatRawBayer8bit"; - case OMX_COLOR_FormatRawBayer10bit: return "OMX_COLOR_FormatRawBayer10bit"; - case OMX_COLOR_FormatRawBayer8bitcompressed: return "OMX_COLOR_FormatRawBayer8bitcompressed"; - case OMX_COLOR_FormatL2: return "OMX_COLOR_FormatL2"; - case OMX_COLOR_FormatL4: return "OMX_COLOR_FormatL4"; - case OMX_COLOR_FormatL8: return "OMX_COLOR_FormatL8"; - case OMX_COLOR_FormatL16: return "OMX_COLOR_FormatL16"; - case OMX_COLOR_FormatL24: return "OMX_COLOR_FormatL24"; - case OMX_COLOR_FormatL32: return "OMX_COLOR_FormatL32"; - case OMX_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_COLOR_FormatYUV422PackedSemiPlanar: return "OMX_COLOR_FormatYUV422PackedSemiPlanar"; - case OMX_COLOR_Format18BitBGR666: return "OMX_COLOR_Format18BitBGR666"; - case OMX_COLOR_Format24BitARGB6666: return "OMX_COLOR_Format24BitARGB6666"; - case OMX_COLOR_Format24BitABGR6666: return "OMX_COLOR_Format24BitABGR6666"; - - case OMX_COLOR_FormatAndroidOpaque: return "OMX_COLOR_FormatAndroidOpaque"; - case OMX_TI_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_TI_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_QCOM_COLOR_FormatYVU420SemiPlanar: return "OMX_QCOM_COLOR_FormatYVU420SemiPlanar"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka"; - case OMX_SEC_COLOR_FormatNV12Tiled: return "OMX_SEC_COLOR_FormatNV12Tiled"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m"; - - // case QOMX_COLOR_FormatYVU420SemiPlanar: return "QOMX_COLOR_FormatYVU420SemiPlanar"; - case QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka: return "QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka"; - case QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka"; - // case QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka"; - // case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed"; - case QOMX_COLOR_Format32bitRGBA8888: return "QOMX_COLOR_Format32bitRGBA8888"; - case QOMX_COLOR_Format32bitRGBA8888Compressed: return "QOMX_COLOR_Format32bitRGBA8888Compressed"; - - default: - return "unkn"; - } -} - - -// ***** encoder functions ***** -OmxEncoder::OmxEncoder(const char* filename, CameraType type, int in_width, int in_height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write) - : in_width_(in_width), in_height_(in_height), width(out_width), height(out_height) { - this->filename = filename; - this->type = type; - this->write = write; - this->fps = fps; - this->remuxing = !h265; - - this->downscale = in_width != out_width || in_height != out_height; - if (this->downscale) { - this->y_ptr2 = (uint8_t *)malloc(this->width*this->height); - this->u_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - this->v_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - } - - auto component = (OMX_STRING)(h265 ? "OMX.qcom.video.encoder.hevc" : "OMX.qcom.video.encoder.avc"); - int err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks); - if (err != OMX_ErrorNone) { - LOGE("error getting codec: %x", err); - } - assert(err == OMX_ErrorNone); - // printf("handle: %p\n", this->handle); - - // setup input port - - OMX_PARAM_PORTDEFINITIONTYPE in_port = {0}; - in_port.nSize = sizeof(in_port); - in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - - in_port.format.video.nFrameWidth = this->width; - in_port.format.video.nFrameHeight = this->height; - in_port.format.video.nStride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - in_port.format.video.nSliceHeight = this->height; - // in_port.nBufferSize = (this->width * this->height * 3) / 2; - in_port.nBufferSize = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_port.format.video.xFramerate = (this->fps * 65536); - in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused; - // in_port.format.video.eColorFormat = OMX_COLOR_FormatYUV420SemiPlanar; - in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - this->in_buf_headers.resize(in_port.nBufferCountActual); - - // setup output port - - OMX_PARAM_PORTDEFINITIONTYPE out_port = {0}; - out_port.nSize = sizeof(out_port); - out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port)); - out_port.format.video.nFrameWidth = this->width; - out_port.format.video.nFrameHeight = this->height; - out_port.format.video.xFramerate = 0; - out_port.format.video.nBitrate = bitrate; - if (h265) { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingHEVC; - } else { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingAVC; - } - out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - this->out_buf_headers.resize(out_port.nBufferCountActual); - - OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0}; - bitrate_type.nSize = sizeof(bitrate_type); - bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - bitrate_type.eControlRate = OMX_Video_ControlRateVariable; - bitrate_type.nTargetBitrate = bitrate; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - - if (h265) { - // setup HEVC - OMX_VIDEO_PARAM_PROFILELEVELTYPE hevc_type = {0}; - OMX_INDEXTYPE index_type = OMX_IndexParamVideoProfileLevelCurrent; - hevc_type.nSize = sizeof(hevc_type); - hevc_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - - hevc_type.eProfile = OMX_VIDEO_HEVCProfileMain; - hevc_type.eLevel = OMX_VIDEO_HEVCHighTierLevel5; - - OMX_CHECK(OMX_SetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - } else { - // setup h264 - OMX_VIDEO_PARAM_AVCTYPE avc = { 0 }; - avc.nSize = sizeof(avc); - avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - - avc.nBFrames = 0; - avc.nPFrames = 15; - - avc.eProfile = OMX_VIDEO_AVCProfileHigh; - avc.eLevel = OMX_VIDEO_AVCLevel31; - - avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB; - avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable; - - avc.nRefFrames = 1; - avc.bUseHadamard = OMX_TRUE; - avc.bEntropyCodingCABAC = OMX_TRUE; - avc.bWeightedPPrediction = OMX_TRUE; - avc.bconstIpred = OMX_TRUE; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - } - - - // for (int i = 0; ; i++) { - // OMX_VIDEO_PARAM_PORTFORMATTYPE video_port_format = {0}; - // video_port_format.nSize = sizeof(video_port_format); - // video_port_format.nIndex = i; - // video_port_format.nPortIndex = PORT_INDEX_IN; - // if (OMX_GetParameter(this->handle, OMX_IndexParamVideoPortFormat, &video_port_format) != OMX_ErrorNone) - // break; - // printf("in %d: compression 0x%x format 0x%x %s\n", i, - // video_port_format.eCompressionFormat, video_port_format.eColorFormat, - // omx_color_fomat_name(video_port_format.eColorFormat)); - // } - - // for (int i=0; i<32; i++) { - // OMX_VIDEO_PARAM_PROFILELEVELTYPE params = {0}; - // params.nSize = sizeof(params); - // params.nPortIndex = PORT_INDEX_OUT; - // params.nProfileIndex = i; - // if (OMX_GetParameter(this->handle, OMX_IndexParamVideoProfileLevelQuerySupported, ¶ms) != OMX_ErrorNone) - // break; - // printf("profile %d level 0x%x\n", params.eProfile, params.eLevel); - // } - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_IN, this, - in_port.nBufferSize)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_OUT, this, - out_port.nBufferSize)); - } - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL)); - - wait_for_state(OMX_StateExecuting); - - // give omx all the output buffers - for (auto &buf : this->out_buf_headers) { - // printf("fill %p\n", this->out_buf_headers[i]); - OMX_CHECK(OMX_FillThisBuffer(this->handle, buf)); - } - - // fill the input free queue - for (auto &buf : this->in_buf_headers) { - this->free_in.push(buf); - } - - LOGE("omx initialized - in: %d - out %d", this->in_buf_headers.size(), this->out_buf_headers.size()); - - service_name = this->type == DriverCam ? "driverEncodeData" : - (this->type == WideRoadCam ? "wideRoadEncodeData" : - (this->remuxing ? "qRoadEncodeData" : "roadEncodeData")); - pm.reset(new PubMaster({service_name})); -} - -void OmxEncoder::callback_handler(OmxEncoder *e) { - // OMX documentation specifies to not empty the buffer from the callback function - // so we use this intermediate handler to copy the buffer for further writing - // and give it back to OMX. We could also send the data over msgq from here. - bool exit = false; - - while (!exit) { - OMX_BUFFERHEADERTYPE *buffer = e->done_out.pop(); - OmxBuffer *new_buffer = (OmxBuffer*)malloc(sizeof(OmxBuffer) + buffer->nFilledLen); - assert(new_buffer); - - new_buffer->header = *buffer; - memcpy(new_buffer->data, buffer->pBuffer + buffer->nOffset, buffer->nFilledLen); - - e->to_write.push(new_buffer); - -#ifdef QCOM2 - if (buffer->nFlags & OMX_BUFFERFLAG_CODECCONFIG) { - buffer->nTimeStamp = 0; - } - - if (buffer->nFlags & OMX_BUFFERFLAG_EOS) { - buffer->nTimeStamp = 0; - } -#endif - - if (buffer->nFlags & OMX_BUFFERFLAG_EOS) { - exit = true; - } - - // give omx back the buffer - // TOOD: fails when shutting down - OMX_CHECK(OMX_FillThisBuffer(e->handle, buffer)); - } -} - -void OmxEncoder::write_and_broadcast_handler(OmxEncoder *e){ - bool exit = false; - - e->segment_num++; - uint32_t idx = 0; - while (!exit) { - OmxBuffer *out_buf = e->to_write.pop(); - - MessageBuilder msg; - auto edata = (e->type == DriverCam) ? msg.initEvent(true).initDriverEncodeData() : - ((e->type == WideRoadCam) ? msg.initEvent(true).initWideRoadEncodeData() : - (e->remuxing ? msg.initEvent(true).initQRoadEncodeData() : msg.initEvent(true).initRoadEncodeData())); - edata.setData(kj::heapArray(out_buf->data, out_buf->header.nFilledLen)); - edata.setTimestampEof(out_buf->header.nTimeStamp); - edata.setIdx(idx++); - edata.setSegmentNum(e->segment_num); - edata.setFlags(out_buf->header.nFlags); - e->pm->send(e->service_name, msg); - - OmxEncoder::handle_out_buf(e, out_buf); - if (out_buf->header.nFlags & OMX_BUFFERFLAG_EOS) { - exit = true; - } - - free(out_buf); - } -} - - -void OmxEncoder::handle_out_buf(OmxEncoder *e, OmxBuffer *out_buf) { - if (!(out_buf->header.nFlags & OMX_BUFFERFLAG_EOS) && e->writer) { - e->writer->write(out_buf->data, - out_buf->header.nFilledLen, - out_buf->header.nTimeStamp, - out_buf->header.nFlags & OMX_BUFFERFLAG_CODECCONFIG, - out_buf->header.nFlags & OMX_BUFFERFLAG_SYNCFRAME); - } -} - -int OmxEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) { - assert(in_width == this->in_width_); - assert(in_height == this->in_height_); - int err; - if (!this->is_open) { - return -1; - } - - // this sometimes freezes... put it outside the encoder lock so we can still trigger rotates... - // THIS IS A REALLY BAD IDEA, but apparently the race has to happen 30 times to trigger this - //pthread_mutex_unlock(&this->lock); - OMX_BUFFERHEADERTYPE* in_buf = nullptr; - while (!this->free_in.try_pop(in_buf, 20)) { - if (do_exit) { - return -1; - } - } - - //pthread_mutex_lock(&this->lock); - - int ret = this->counter; - - uint8_t *in_buf_ptr = in_buf->pBuffer; - // printf("in_buf ptr %p\n", in_buf_ptr); - - uint8_t *in_y_ptr = in_buf_ptr; - int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, this->width); - // uint8_t *in_uv_ptr = in_buf_ptr + (this->width * this->height); - uint8_t *in_uv_ptr = in_buf_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, this->height)); - - if (this->downscale) { - I420Scale(y_ptr, in_width, - u_ptr, in_width/2, - v_ptr, in_width/2, - in_width, in_height, - this->y_ptr2, this->width, - this->u_ptr2, this->width/2, - this->v_ptr2, this->width/2, - this->width, this->height, - libyuv::kFilterNone); - y_ptr = this->y_ptr2; - u_ptr = this->u_ptr2; - v_ptr = this->v_ptr2; - } - err = libyuv::I420ToNV12(y_ptr, this->width, - u_ptr, this->width/2, - v_ptr, this->width/2, - in_y_ptr, in_y_stride, - in_uv_ptr, in_uv_stride, - this->width, this->height); - assert(err == 0); - - // in_buf->nFilledLen = (this->width*this->height) + (this->width*this->height/2); - in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME; - in_buf->nOffset = 0; - in_buf->nTimeStamp = ts/1000LL; // OMX_TICKS, in microseconds - this->last_t = in_buf->nTimeStamp; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - this->dirty = true; - - this->counter++; - - return ret; -} - -void OmxEncoder::encoder_open(const char* path) { - if (this->write) { - writer.reset(new VideoWriter(path, this->filename, this->remuxing, this->width, this->height, this->fps, !this->remuxing, false)); - } - - // start writer threads - callback_handler_thread = std::thread(OmxEncoder::callback_handler, this); - write_handler_thread = std::thread(OmxEncoder::write_and_broadcast_handler, this); - - this->is_open = true; - this->counter = 0; -} - -void OmxEncoder::encoder_close() { - if (this->is_open) { - if (this->dirty) { - // drain output only if there could be frames in the encoder - - OMX_BUFFERHEADERTYPE* in_buf = this->free_in.pop(); - in_buf->nFilledLen = 0; - in_buf->nOffset = 0; - in_buf->nFlags = OMX_BUFFERFLAG_EOS; - in_buf->nTimeStamp = this->last_t + 1000000LL/this->fps; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - this->dirty = false; - } - - callback_handler_thread.join(); - write_handler_thread.join(); - - writer.reset(); - } - this->is_open = false; -} - -OmxEncoder::~OmxEncoder() { - assert(!this->is_open); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_IN, buf)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, buf)); - } - - wait_for_state(OMX_StateLoaded); - - OMX_CHECK(OMX_FreeHandle(this->handle)); - - OMX_BUFFERHEADERTYPE *buf; - while (this->free_in.try_pop(buf)); - while (this->done_out.try_pop(buf)); - - OmxBuffer *write_buf; - while (this->to_write.try_pop(write_buf)) { - free(write_buf); - }; - - if (this->downscale) { - free(this->y_ptr2); - free(this->u_ptr2); - free(this->v_ptr2); - } -} diff --git a/selfdrive/loggerd/omx_encoder.h b/selfdrive/loggerd/omx_encoder.h deleted file mode 100644 index e57dccbe11..0000000000 --- a/selfdrive/loggerd/omx_encoder.h +++ /dev/null @@ -1,79 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include - -#include "selfdrive/common/queue.h" -#include "selfdrive/loggerd/encoder.h" -#include "selfdrive/loggerd/video_writer.h" - -struct OmxBuffer { - OMX_BUFFERHEADERTYPE header; - OMX_U8 data[]; -}; - - -// OmxEncoder, lossey codec using hardware hevc -class OmxEncoder : public VideoEncoder { -public: - OmxEncoder(const char* filename, CameraType type, int width, int height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write = true); - ~OmxEncoder(); - int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts); - void encoder_open(const char* path); - void encoder_close(); - - // OMX callbacks - static OMX_ERRORTYPE event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data); - static OMX_ERRORTYPE empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - static OMX_ERRORTYPE fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - -private: - void wait_for_state(OMX_STATETYPE state); - static void callback_handler(OmxEncoder *e); - static void write_and_broadcast_handler(OmxEncoder *e); - static void handle_out_buf(OmxEncoder *e, OmxBuffer *out_buf); - - int in_width_, in_height_; - int width, height, fps; - bool is_open = false; - bool dirty = false; - bool write = false; - int counter = 0; - std::thread callback_handler_thread; - std::thread write_handler_thread; - int segment_num = -1; - std::unique_ptr pm; - const char *service_name; - - const char* filename; - CameraType type; - - std::mutex state_lock; - std::condition_variable state_cv; - OMX_STATETYPE state = OMX_StateLoaded; - - OMX_HANDLETYPE handle; - - std::vector in_buf_headers; - std::vector out_buf_headers; - - uint64_t last_t; - - SafeQueue free_in; - SafeQueue done_out; - SafeQueue to_write; - - bool remuxing; - std::unique_ptr writer; - - bool downscale; - uint8_t *y_ptr2, *u_ptr2, *v_ptr2; -}; diff --git a/selfdrive/loggerd/raw_logger.cc b/selfdrive/loggerd/raw_logger.cc index 29d421a881..72c8d0d93e 100644 --- a/selfdrive/loggerd/raw_logger.cc +++ b/selfdrive/loggerd/raw_logger.cc @@ -59,7 +59,7 @@ void RawLogger::encoder_close() { } int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts) { + int in_width, int in_height, VisionIpcBufExtra *extra) { assert(in_width == this->in_width_); assert(in_height == this->in_height_); diff --git a/selfdrive/loggerd/raw_logger.h b/selfdrive/loggerd/raw_logger.h index 56bd08ff1f..14c4a61ea0 100644 --- a/selfdrive/loggerd/raw_logger.h +++ b/selfdrive/loggerd/raw_logger.h @@ -12,6 +12,7 @@ extern "C" { } #include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/loggerd.h" #include "selfdrive/loggerd/video_writer.h" class RawLogger : public VideoEncoder { @@ -20,7 +21,7 @@ class RawLogger : public VideoEncoder { int bitrate, bool h265, int out_width, int out_height, bool write = true); ~RawLogger(); int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, - int in_width, int in_height, uint64_t ts); + int in_width, int in_height, VisionIpcBufExtra *extra); void encoder_open(const char* path); void encoder_close(); diff --git a/selfdrive/loggerd/remote_encoder.cc b/selfdrive/loggerd/remote_encoder.cc new file mode 100644 index 0000000000..c79595b0fe --- /dev/null +++ b/selfdrive/loggerd/remote_encoder.cc @@ -0,0 +1,84 @@ +#include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/remote_encoder.h" + +int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct RemoteEncoder &re) { + const LogCameraInfo &cam_info = (name == "driverEncodeData") ? cameras_logged[1] : + ((name == "wideRoadEncodeData") ? cameras_logged[2] : + ((name == "qRoadEncodeData") ? qcam_info : cameras_logged[0])); + if (!cam_info.record) return 0; // TODO: handle this by not subscribing + + int bytes_count = 0; + + // TODO: AlignedBuffer is making a copy and allocing + //AlignedBuffer aligned_buf; + //capnp::FlatArrayMessageReader cmsg(aligned_buf.align(msg->getData(), msg->getSize())); + capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize())); + auto event = cmsg.getRoot(); + auto edata = (name == "driverEncodeData") ? event.getDriverEncodeData() : + ((name == "wideRoadEncodeData") ? event.getWideRoadEncodeData() : + ((name == "qRoadEncodeData") ? event.getQRoadEncodeData() : event.getRoadEncodeData())); + auto idx = edata.getIdx(); + auto flags = idx.getFlags(); + + // rotation happened, process the queue (happens before the current message) + if (re.logger_segment != s->rotate_segment) { + re.logger_segment = s->rotate_segment; + for (auto &qmsg: re.q) { + bytes_count += handle_encoder_msg(s, qmsg, name, re); + } + re.q.clear(); + } + + if (!re.writer) { + // only create on iframe + if (flags & V4L2_BUF_FLAG_KEYFRAME) { + if (re.dropped_frames) { + // this should only happen for the first segment, maybe + LOGD("%s: dropped %d non iframe packets before init", name.c_str(), re.dropped_frames); + re.dropped_frames = 0; + } + re.writer.reset(new VideoWriter(s->segment_path, + cam_info.filename, !cam_info.is_h265, + cam_info.frame_width, cam_info.frame_height, + cam_info.fps, cam_info.is_h265, false)); + // write the header + auto header = edata.getHeader(); + re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); + re.segment = idx.getSegmentNum(); + } else { + ++re.dropped_frames; + return bytes_count; + } + } + + if (re.segment != idx.getSegmentNum()) { + if (re.writer) { + // encoder is on the next segment, this segment is over so we close the videowriter + re.writer.reset(); + ++s->ready_to_rotate; + LOGD("rotate %d -> %d ready %d/%d", re.segment, idx.getSegmentNum(), s->ready_to_rotate.load(), s->max_waiting); + } + // queue up all the new segment messages, they go in after the rotate + re.q.push_back(msg); + } else { + auto data = edata.getData(); + re.writer->write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); + + // put it in log stream as the idx packet + MessageBuilder bmsg; + auto evt = bmsg.initEvent(event.getValid()); + evt.setLogMonoTime(event.getLogMonoTime()); + if (name == "driverEncodeData") { evt.setDriverEncodeIdx(idx); } + if (name == "wideRoadEncodeData") { evt.setWideRoadEncodeIdx(idx); } + if (name == "qRoadEncodeData") { evt.setQRoadEncodeIdx(idx); } + if (name == "roadEncodeData") { evt.setRoadEncodeIdx(idx); } + auto new_msg = bmsg.toBytes(); + logger_log(&s->logger, (uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? + delete msg; + bytes_count += new_msg.size(); + } + + return bytes_count; +} + + diff --git a/selfdrive/loggerd/remote_encoder.h b/selfdrive/loggerd/remote_encoder.h new file mode 100644 index 0000000000..6fc91a2209 --- /dev/null +++ b/selfdrive/loggerd/remote_encoder.h @@ -0,0 +1,12 @@ +#include "selfdrive/loggerd/video_writer.h" +#define V4L2_BUF_FLAG_KEYFRAME 0x00000008 + +struct RemoteEncoder { + std::unique_ptr writer; + int segment = -1; + std::vector q; + int logger_segment = -1; + int dropped_frames = 0; +}; + +int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct RemoteEncoder &re); \ No newline at end of file diff --git a/selfdrive/loggerd/tests/test_encoder.py b/selfdrive/loggerd/tests/test_encoder.py index 9479b6256a..760c255443 100755 --- a/selfdrive/loggerd/tests/test_encoder.py +++ b/selfdrive/loggerd/tests/test_encoder.py @@ -107,7 +107,8 @@ class TestEncoder(unittest.TestCase): # sanity check file size file_size = os.path.getsize(file_path) - self.assertTrue(math.isclose(file_size, size, rel_tol=FILE_SIZE_TOLERANCE)) + self.assertTrue(math.isclose(file_size, size, rel_tol=FILE_SIZE_TOLERANCE), + f"{file_path} size {file_size} isn't close to target size {size}") # Check encodeIdx if encode_idx_name is not None: diff --git a/selfdrive/loggerd/v4l_encoder.cc b/selfdrive/loggerd/v4l_encoder.cc new file mode 100644 index 0000000000..b61bf01019 --- /dev/null +++ b/selfdrive/loggerd/v4l_encoder.cc @@ -0,0 +1,401 @@ +#include +#include +#include + +#include "selfdrive/loggerd/v4l_encoder.h" +#include "selfdrive/common/util.h" +#include "selfdrive/common/timing.h" + +#include "libyuv.h" +#include "msm_media_info.h" + +// has to be in this order +#include "v4l2-controls.h" +#include +#define V4L2_QCOM_BUF_FLAG_CODECCONFIG 0x00020000 +#define V4L2_QCOM_BUF_FLAG_EOS 0x02000000 + +// echo 0x7fffffff > /sys/kernel/debug/msm_vidc/debug_level +const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0; + +#define checked_ioctl(x,y,z) { int _ret = HANDLE_EINTR(ioctl(x,y,z)); if (_ret!=0) { LOGE("checked_ioctl failed %d %lx %p", x, y, z); } assert(_ret==0); } + +static void dequeue_buffer(int fd, v4l2_buf_type buf_type, unsigned int *index=NULL, unsigned int *bytesused=NULL, unsigned int *flags=NULL, struct timeval *timestamp=NULL) { + v4l2_plane plane = {0}; + v4l2_buffer v4l_buf = { + .type = buf_type, + .memory = V4L2_MEMORY_USERPTR, + .m = { .planes = &plane, }, + .length = 1, + }; + checked_ioctl(fd, VIDIOC_DQBUF, &v4l_buf); + + if (index) *index = v4l_buf.index; + if (bytesused) *bytesused = v4l_buf.m.planes[0].bytesused; + if (flags) *flags = v4l_buf.flags; + if (timestamp) *timestamp = v4l_buf.timestamp; + assert(v4l_buf.m.planes[0].data_offset == 0); +} + +static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, VisionBuf *buf, struct timeval timestamp={0}) { + v4l2_plane plane = { + .length = (unsigned int)buf->len, + .m = { .userptr = (unsigned long)buf->addr, }, + .reserved = {(unsigned int)buf->fd} + }; + + v4l2_buffer v4l_buf = { + .type = buf_type, + .index = index, + .memory = V4L2_MEMORY_USERPTR, + .m = { .planes = &plane, }, + .length = 1, + .bytesused = 0, + .flags = V4L2_BUF_FLAG_TIMESTAMP_COPY, + .timestamp = timestamp + }; + + checked_ioctl(fd, VIDIOC_QBUF, &v4l_buf); +} + +static void request_buffers(int fd, v4l2_buf_type buf_type, unsigned int count) { + struct v4l2_requestbuffers reqbuf = { + .type = buf_type, + .memory = V4L2_MEMORY_USERPTR, + .count = count + }; + checked_ioctl(fd, VIDIOC_REQBUFS, &reqbuf); +} + +// TODO: writing should be moved to loggerd +void V4LEncoder::write_handler(V4LEncoder *e, const char *path) { + VideoWriter writer(path, e->filename, !e->h265, e->width, e->height, e->fps, e->h265, false); + + bool first = true; + kj::Array* out_buf; + while ((out_buf = e->to_write.pop())) { + capnp::FlatArrayMessageReader cmsg(*out_buf); + cereal::Event::Reader event = cmsg.getRoot(); + + auto edata = (e->type == DriverCam) ? event.getDriverEncodeData() : + ((e->type == WideRoadCam) ? event.getWideRoadEncodeData() : + (e->h265 ? event.getRoadEncodeData() : event.getQRoadEncodeData())); + auto idx = edata.getIdx(); + auto flags = idx.getFlags(); + + if (first) { + assert(flags & V4L2_BUF_FLAG_KEYFRAME); + auto header = edata.getHeader(); + writer.write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); + first = false; + } + + // dangerous cast from const, but should be fine + auto data = edata.getData(); + if (data.size() > 0) { + writer.write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); + } + + // free the data + delete out_buf; + } + + // VideoWriter is freed on out of scope +} + +void V4LEncoder::dequeue_handler(V4LEncoder *e) { + std::string dequeue_thread_name = "dq-"+std::string(e->filename); + util::set_thread_name(dequeue_thread_name.c_str()); + + e->segment_num++; + uint32_t idx = -1; + bool exit = false; + + // POLLIN is capture, POLLOUT is frame + struct pollfd pfd; + pfd.events = POLLIN | POLLOUT; + pfd.fd = e->fd; + + // save the header + kj::Array header; + + while (!exit) { + int rc = poll(&pfd, 1, 1000); + if (!rc) { LOGE("encoder dequeue poll timeout"); continue; } + + if (env_debug_encoder >= 2) { + printf("%20s poll %x at %.2f ms\n", e->filename, pfd.revents, millis_since_boot()); + } + + int frame_id = -1; + if (pfd.revents & POLLIN) { + unsigned int bytesused, flags, index; + struct timeval timestamp; + dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, &index, &bytesused, &flags, ×tamp); + e->buf_out[index].sync(VISIONBUF_SYNC_FROM_DEVICE); + uint8_t *buf = (uint8_t*)e->buf_out[index].addr; + int64_t ts = timestamp.tv_sec * 1000000 + timestamp.tv_usec; + + // eof packet, we exit + if (flags & V4L2_QCOM_BUF_FLAG_EOS) { + if (e->write) e->to_write.push(NULL); + exit = true; + } else if (flags & V4L2_QCOM_BUF_FLAG_CODECCONFIG) { + // save header + header = kj::heapArray(buf, bytesused); + } else { + VisionIpcBufExtra extra = e->extras.pop(); + assert(extra.timestamp_eof/1000 == ts); // stay in sync + + frame_id = extra.frame_id; + ++idx; + + // broadcast packet + MessageBuilder msg; + auto event = msg.initEvent(true); + auto edat = (e->type == DriverCam) ? event.initDriverEncodeData() : + ((e->type == WideRoadCam) ? event.initWideRoadEncodeData() : + (e->h265 ? event.initRoadEncodeData() : event.initQRoadEncodeData())); + auto edata = edat.initIdx(); + edata.setFrameId(extra.frame_id); + edata.setTimestampSof(extra.timestamp_sof); + edata.setTimestampEof(extra.timestamp_eof); + edata.setType(e->h265 ? cereal::EncodeIndex::Type::FULL_H_E_V_C : cereal::EncodeIndex::Type::QCAMERA_H264); + edata.setEncodeId(idx); + edata.setSegmentNum(e->segment_num); + edata.setSegmentId(idx); + edata.setFlags(flags); + edata.setLen(bytesused); + edat.setData(kj::arrayPtr(buf, bytesused)); + if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); + + auto words = new kj::Array(capnp::messageToFlatArray(msg)); + auto bytes = words->asBytes(); + e->pm->send(e->service_name, bytes.begin(), bytes.size()); + if (e->write) { + e->to_write.push(words); + } else { + delete words; + } + } + + if (env_debug_encoder) { + printf("%20s got(%d) %6d bytes flags %8x idx %4d id %8d ts %ld lat %.2f ms (%lu frames free)\n", + e->filename, index, bytesused, flags, idx, frame_id, ts, millis_since_boot()-(ts/1000.), e->free_buf_in.size()); + } + + // requeue the buffer + queue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, index, &e->buf_out[index]); + } + + if (pfd.revents & POLLOUT) { + unsigned int index; + dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, &index); + e->free_buf_in.push(index); + } + } +} + +V4LEncoder::V4LEncoder( + const char* filename, CameraType type, int in_width, int in_height, + int fps, int bitrate, bool h265, int out_width, int out_height, bool write) + : type(type), in_width_(in_width), in_height_(in_height), + filename(filename), h265(h265), + width(out_width), height(out_height), fps(fps), write(write) { + fd = open("/dev/v4l/by-path/platform-aa00000.qcom_vidc-video-index1", O_RDWR|O_NONBLOCK); + assert(fd >= 0); + + struct v4l2_capability cap; + checked_ioctl(fd, VIDIOC_QUERYCAP, &cap); + LOGD("opened encoder device %s %s = %d", cap.driver, cap.card, fd); + assert(strcmp((const char *)cap.driver, "msm_vidc_driver") == 0); + assert(strcmp((const char *)cap.card, "msm_vidc_venc") == 0); + + struct v4l2_format fmt_out = { + .type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, + .fmt = { + .pix_mp = { + // downscales are free with v4l + .width = (unsigned int)out_width, + .height = (unsigned int)out_height, + .pixelformat = h265 ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, + .field = V4L2_FIELD_ANY, + .colorspace = V4L2_COLORSPACE_DEFAULT, + } + } + }; + checked_ioctl(fd, VIDIOC_S_FMT, &fmt_out); + + v4l2_streamparm streamparm = { + .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, + .parm = { + .output = { + // TODO: more stuff here? we don't know + .timeperframe = { + .numerator = 1, + .denominator = 20 + } + } + } + }; + checked_ioctl(fd, VIDIOC_S_PARM, &streamparm); + + struct v4l2_format fmt_in = { + .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, + .fmt = { + .pix_mp = { + .width = (unsigned int)in_width, + .height = (unsigned int)in_height, + .pixelformat = V4L2_PIX_FMT_NV12, + .field = V4L2_FIELD_ANY, + .colorspace = V4L2_COLORSPACE_470_SYSTEM_BG, + } + } + }; + checked_ioctl(fd, VIDIOC_S_FMT, &fmt_in); + + LOGD("in buffer size %d, out buffer size %d", + fmt_in.fmt.pix_mp.plane_fmt[0].sizeimage, + fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); + + // shared ctrls + { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDEO_HEADER_MODE, .value = V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE}, + { .id = V4L2_CID_MPEG_VIDEO_BITRATE, .value = bitrate}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL, .value = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY, .value = V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD, .value = 1}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } + + if (h265) { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 29}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } else { + struct v4l2_control ctrls[] = { + { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 15}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, + { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA, .value = 0}, + { .id = V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE, .value = 0}, + }; + for (auto ctrl : ctrls) { + checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); + } + } + + // allocate buffers + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, BUF_OUT_COUNT); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, BUF_IN_COUNT); + + // start encoder + v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); + buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); + + // queue up output buffers + for (unsigned int i = 0; i < BUF_OUT_COUNT; i++) { + buf_out[i].allocate(fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); + queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, i, &buf_out[i]); + } + // queue up input buffers + for (unsigned int i = 0; i < BUF_IN_COUNT; i++) { + buf_in[i].allocate(fmt_in.fmt.pix_mp.plane_fmt[0].sizeimage); + free_buf_in.push(i); + } + + // publish + service_name = this->type == DriverCam ? "driverEncodeData" : + (this->type == WideRoadCam ? "wideRoadEncodeData" : + (this->h265 ? "roadEncodeData" : "qRoadEncodeData")); + pm.reset(new PubMaster({service_name})); +} + + +void V4LEncoder::encoder_open(const char* path) { + dequeue_handler_thread = std::thread(V4LEncoder::dequeue_handler, this); + if (this->write) write_handler_thread = std::thread(V4LEncoder::write_handler, this, path); + this->is_open = true; + this->counter = 0; +} + +int V4LEncoder::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width, int in_height, VisionIpcBufExtra *extra) { + assert(in_width == in_width_); + assert(in_height == in_height_); + assert(is_open); + + // reserve buffer + int buffer_in = free_buf_in.pop(); + + uint8_t *in_y_ptr = (uint8_t*)buf_in[buffer_in].addr; + int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, in_width); + int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, in_width); + uint8_t *in_uv_ptr = in_y_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, in_height)); + + // GRRR COPY + int err = libyuv::I420ToNV12(y_ptr, in_width, + u_ptr, in_width/2, + v_ptr, in_width/2, + in_y_ptr, in_y_stride, + in_uv_ptr, in_uv_stride, + in_width, in_height); + assert(err == 0); + + struct timeval timestamp { + .tv_sec = (long)(extra->timestamp_eof/1000000000), + .tv_usec = (long)((extra->timestamp_eof/1000) % 1000000), + }; + + // push buffer + extras.push(*extra); + buf_in[buffer_in].sync(VISIONBUF_SYNC_TO_DEVICE); + queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, buffer_in, &buf_in[buffer_in], timestamp); + + return this->counter++; +} + +void V4LEncoder::encoder_close() { + if (this->is_open) { + // pop all the frames before closing, then put the buffers back + for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.pop(); + for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.push(i); + // no frames, stop the encoder + struct v4l2_encoder_cmd encoder_cmd = { .cmd = V4L2_ENC_CMD_STOP }; + checked_ioctl(fd, VIDIOC_ENCODER_CMD, &encoder_cmd); + // join waits for V4L2_QCOM_BUF_FLAG_EOS + dequeue_handler_thread.join(); + assert(extras.empty()); + if (this->write) write_handler_thread.join(); + assert(to_write.empty()); + } + this->is_open = false; +} + +V4LEncoder::~V4LEncoder() { + encoder_close(); + v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, 0); + buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); + request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, 0); + close(fd); +} diff --git a/selfdrive/loggerd/v4l_encoder.h b/selfdrive/loggerd/v4l_encoder.h new file mode 100644 index 0000000000..43b70baebd --- /dev/null +++ b/selfdrive/loggerd/v4l_encoder.h @@ -0,0 +1,48 @@ +#pragma once + +#include "selfdrive/common/queue.h" +#include "selfdrive/loggerd/encoder.h" +#include "selfdrive/loggerd/loggerd.h" +#include "selfdrive/loggerd/video_writer.h" + +#define BUF_IN_COUNT 7 +#define BUF_OUT_COUNT 6 + +class V4LEncoder : public VideoEncoder { +public: + V4LEncoder(const char* filename, CameraType type, int width, int height, int fps, int bitrate, bool h265, int out_width, int out_height, bool write = true); + ~V4LEncoder(); + int encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, + int in_width, int in_height, VisionIpcBufExtra *extra); + void encoder_open(const char* path); + void encoder_close(); +private: + int fd; + + const char* filename; + CameraType type; + unsigned int in_width_, in_height_; + bool h265; + bool is_open = false; + int segment_num = -1; + int counter = 0; + + std::unique_ptr pm; + const char *service_name; + + static void dequeue_handler(V4LEncoder *e); + std::thread dequeue_handler_thread; + + VisionBuf buf_in[BUF_IN_COUNT]; + VisionBuf buf_out[BUF_OUT_COUNT]; + SafeQueue free_buf_in; + + SafeQueue extras; + + // writing support + int width, height, fps; + bool write; + static void write_handler(V4LEncoder *e, const char *path); + std::thread write_handler_thread; + SafeQueue* > to_write; +}; diff --git a/selfdrive/loggerd/video_writer.cc b/selfdrive/loggerd/video_writer.cc index f9034f6912..51e606dc5c 100644 --- a/selfdrive/loggerd/video_writer.cc +++ b/selfdrive/loggerd/video_writer.cc @@ -48,7 +48,6 @@ VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, int err = avio_open(&this->ofmt_ctx->pb, this->vid_path.c_str(), AVIO_FLAG_WRITE); assert(err >= 0); - this->wrote_codec_config = false; } else { this->of = util::safe_fopen(this->vid_path.c_str(), "wb"); assert(this->of); diff --git a/selfdrive/loggerd/video_writer.h b/selfdrive/loggerd/video_writer.h index 8217b859bf..8048d93a07 100644 --- a/selfdrive/loggerd/video_writer.h +++ b/selfdrive/loggerd/video_writer.h @@ -20,6 +20,4 @@ private: AVFormatContext *ofmt_ctx; AVStream *out_stream; bool remuxing, raw; - - bool wrote_codec_config; }; \ No newline at end of file diff --git a/selfdrive/loggerd/include/msm_media_info.h b/third_party/linux/include/msm_media_info.h similarity index 100% rename from selfdrive/loggerd/include/msm_media_info.h rename to third_party/linux/include/msm_media_info.h diff --git a/third_party/linux/include/v4l2-controls.h b/third_party/linux/include/v4l2-controls.h new file mode 100644 index 0000000000..d14cd8fabe --- /dev/null +++ b/third_party/linux/include/v4l2-controls.h @@ -0,0 +1,1696 @@ +/* + * Video for Linux Two controls header file + * + * Copyright (C) 1999-2012 the contributors + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * Alternatively you can redistribute this file under the terms of the + * BSD license as stated below: + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. The names of its contributors may not be used to endorse or promote + * products derived from this software without specific prior written + * permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR + * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT + * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED + * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR + * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * The contents of this header was split off from videodev2.h. All control + * definitions should be added to this header, which is included by + * videodev2.h. + */ + +#ifndef __LINUX_V4L2_CONTROLS_H +#define __LINUX_V4L2_CONTROLS_H + +/* Control classes */ +#define V4L2_CTRL_CLASS_USER 0x00980000 /* Old-style 'user' controls */ +#define V4L2_CTRL_CLASS_MPEG 0x00990000 /* MPEG-compression controls */ +#define V4L2_CTRL_CLASS_CAMERA 0x009a0000 /* Camera class controls */ +#define V4L2_CTRL_CLASS_FM_TX 0x009b0000 /* FM Modulator controls */ +#define V4L2_CTRL_CLASS_FLASH 0x009c0000 /* Camera flash controls */ +#define V4L2_CTRL_CLASS_JPEG 0x009d0000 /* JPEG-compression controls */ +#define V4L2_CTRL_CLASS_IMAGE_SOURCE 0x009e0000 /* Image source controls */ +#define V4L2_CTRL_CLASS_IMAGE_PROC 0x009f0000 /* Image processing controls */ +#define V4L2_CTRL_CLASS_DV 0x00a00000 /* Digital Video controls */ +#define V4L2_CTRL_CLASS_FM_RX 0x00a10000 /* FM Receiver controls */ +#define V4L2_CTRL_CLASS_RF_TUNER 0x00a20000 /* RF tuner controls */ +#define V4L2_CTRL_CLASS_DETECT 0x00a30000 /* Detection controls */ + +/* User-class control IDs */ + +#define V4L2_CID_BASE (V4L2_CTRL_CLASS_USER | 0x900) +#define V4L2_CID_USER_BASE V4L2_CID_BASE +#define V4L2_CID_USER_CLASS (V4L2_CTRL_CLASS_USER | 1) +#define V4L2_CID_BRIGHTNESS (V4L2_CID_BASE+0) +#define V4L2_CID_CONTRAST (V4L2_CID_BASE+1) +#define V4L2_CID_SATURATION (V4L2_CID_BASE+2) +#define V4L2_CID_HUE (V4L2_CID_BASE+3) +#define V4L2_CID_AUDIO_VOLUME (V4L2_CID_BASE+5) +#define V4L2_CID_AUDIO_BALANCE (V4L2_CID_BASE+6) +#define V4L2_CID_AUDIO_BASS (V4L2_CID_BASE+7) +#define V4L2_CID_AUDIO_TREBLE (V4L2_CID_BASE+8) +#define V4L2_CID_AUDIO_MUTE (V4L2_CID_BASE+9) +#define V4L2_CID_AUDIO_LOUDNESS (V4L2_CID_BASE+10) +#define V4L2_CID_BLACK_LEVEL (V4L2_CID_BASE+11) /* Deprecated */ +#define V4L2_CID_AUTO_WHITE_BALANCE (V4L2_CID_BASE+12) +#define V4L2_CID_DO_WHITE_BALANCE (V4L2_CID_BASE+13) +#define V4L2_CID_RED_BALANCE (V4L2_CID_BASE+14) +#define V4L2_CID_BLUE_BALANCE (V4L2_CID_BASE+15) +#define V4L2_CID_GAMMA (V4L2_CID_BASE+16) +#define V4L2_CID_WHITENESS (V4L2_CID_GAMMA) /* Deprecated */ +#define V4L2_CID_EXPOSURE (V4L2_CID_BASE+17) +#define V4L2_CID_AUTOGAIN (V4L2_CID_BASE+18) +#define V4L2_CID_GAIN (V4L2_CID_BASE+19) +#define V4L2_CID_HFLIP (V4L2_CID_BASE+20) +#define V4L2_CID_VFLIP (V4L2_CID_BASE+21) + +#define V4L2_CID_POWER_LINE_FREQUENCY (V4L2_CID_BASE+24) +enum v4l2_power_line_frequency { + V4L2_CID_POWER_LINE_FREQUENCY_DISABLED = 0, + V4L2_CID_POWER_LINE_FREQUENCY_50HZ = 1, + V4L2_CID_POWER_LINE_FREQUENCY_60HZ = 2, + V4L2_CID_POWER_LINE_FREQUENCY_AUTO = 3, +}; +#define V4L2_CID_HUE_AUTO (V4L2_CID_BASE+25) +#define V4L2_CID_WHITE_BALANCE_TEMPERATURE (V4L2_CID_BASE+26) +#define V4L2_CID_SHARPNESS (V4L2_CID_BASE+27) +#define V4L2_CID_BACKLIGHT_COMPENSATION (V4L2_CID_BASE+28) +#define V4L2_CID_CHROMA_AGC (V4L2_CID_BASE+29) +#define V4L2_CID_COLOR_KILLER (V4L2_CID_BASE+30) +#define V4L2_CID_COLORFX (V4L2_CID_BASE+31) +enum v4l2_colorfx { + V4L2_COLORFX_NONE = 0, + V4L2_COLORFX_BW = 1, + V4L2_COLORFX_SEPIA = 2, + V4L2_COLORFX_NEGATIVE = 3, + V4L2_COLORFX_EMBOSS = 4, + V4L2_COLORFX_SKETCH = 5, + V4L2_COLORFX_SKY_BLUE = 6, + V4L2_COLORFX_GRASS_GREEN = 7, + V4L2_COLORFX_SKIN_WHITEN = 8, + V4L2_COLORFX_VIVID = 9, + V4L2_COLORFX_AQUA = 10, + V4L2_COLORFX_ART_FREEZE = 11, + V4L2_COLORFX_SILHOUETTE = 12, + V4L2_COLORFX_SOLARIZATION = 13, + V4L2_COLORFX_ANTIQUE = 14, + V4L2_COLORFX_SET_CBCR = 15, +}; +#define V4L2_CID_AUTOBRIGHTNESS (V4L2_CID_BASE+32) +#define V4L2_CID_BAND_STOP_FILTER (V4L2_CID_BASE+33) + +#define V4L2_CID_ROTATE (V4L2_CID_BASE+34) +#define V4L2_CID_BG_COLOR (V4L2_CID_BASE+35) + +#define V4L2_CID_CHROMA_GAIN (V4L2_CID_BASE+36) + +#define V4L2_CID_ILLUMINATORS_1 (V4L2_CID_BASE+37) +#define V4L2_CID_ILLUMINATORS_2 (V4L2_CID_BASE+38) + +#define V4L2_CID_MIN_BUFFERS_FOR_CAPTURE (V4L2_CID_BASE+39) +#define V4L2_CID_MIN_BUFFERS_FOR_OUTPUT (V4L2_CID_BASE+40) + +#define V4L2_CID_ALPHA_COMPONENT (V4L2_CID_BASE+41) +#define V4L2_CID_COLORFX_CBCR (V4L2_CID_BASE+42) + +/* last CID + 1 */ +#define V4L2_CID_LASTP1 (V4L2_CID_BASE+43) + +/* USER-class private control IDs */ + +/* The base for the meye driver controls. See linux/meye.h for the list + * of controls. We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_MEYE_BASE (V4L2_CID_USER_BASE + 0x1000) + +/* The base for the bttv driver controls. + * We reserve 32 controls for this driver. */ +#define V4L2_CID_USER_BTTV_BASE (V4L2_CID_USER_BASE + 0x1010) + + +/* The base for the s2255 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_S2255_BASE (V4L2_CID_USER_BASE + 0x1030) + +/* + * The base for the si476x driver controls. See include/media/drv-intf/si476x.h + * for the list of controls. Total of 16 controls is reserved for this driver + */ +#define V4L2_CID_USER_SI476X_BASE (V4L2_CID_USER_BASE + 0x1040) + +/* The base for the TI VPE driver controls. Total of 16 controls is reserved for + * this driver */ +#define V4L2_CID_USER_TI_VPE_BASE (V4L2_CID_USER_BASE + 0x1050) + +/* The base for the saa7134 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_SAA7134_BASE (V4L2_CID_USER_BASE + 0x1060) + +/* The base for the adv7180 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_ADV7180_BASE (V4L2_CID_USER_BASE + 0x1070) + +/* The base for the tc358743 driver controls. + * We reserve 16 controls for this driver. */ +#define V4L2_CID_USER_TC358743_BASE (V4L2_CID_USER_BASE + 0x1080) + +/* MPEG-class control IDs */ +/* The MPEG controls are applicable to all codec controls + * and the 'MPEG' part of the define is historical */ + +#define V4L2_CID_MPEG_BASE (V4L2_CTRL_CLASS_MPEG | 0x900) +#define V4L2_CID_MPEG_CLASS (V4L2_CTRL_CLASS_MPEG | 1) + +/* MPEG streams, specific to multiplexed streams */ +#define V4L2_CID_MPEG_STREAM_TYPE (V4L2_CID_MPEG_BASE+0) +enum v4l2_mpeg_stream_type { + V4L2_MPEG_STREAM_TYPE_MPEG2_PS = 0, /* MPEG-2 program stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_TS = 1, /* MPEG-2 transport stream */ + V4L2_MPEG_STREAM_TYPE_MPEG1_SS = 2, /* MPEG-1 system stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_DVD = 3, /* MPEG-2 DVD-compatible stream */ + V4L2_MPEG_STREAM_TYPE_MPEG1_VCD = 4, /* MPEG-1 VCD-compatible stream */ + V4L2_MPEG_STREAM_TYPE_MPEG2_SVCD = 5, /* MPEG-2 SVCD-compatible stream */ +}; +#define V4L2_CID_MPEG_STREAM_PID_PMT (V4L2_CID_MPEG_BASE+1) +#define V4L2_CID_MPEG_STREAM_PID_AUDIO (V4L2_CID_MPEG_BASE+2) +#define V4L2_CID_MPEG_STREAM_PID_VIDEO (V4L2_CID_MPEG_BASE+3) +#define V4L2_CID_MPEG_STREAM_PID_PCR (V4L2_CID_MPEG_BASE+4) +#define V4L2_CID_MPEG_STREAM_PES_ID_AUDIO (V4L2_CID_MPEG_BASE+5) +#define V4L2_CID_MPEG_STREAM_PES_ID_VIDEO (V4L2_CID_MPEG_BASE+6) +#define V4L2_CID_MPEG_STREAM_VBI_FMT (V4L2_CID_MPEG_BASE+7) +enum v4l2_mpeg_stream_vbi_fmt { + V4L2_MPEG_STREAM_VBI_FMT_NONE = 0, /* No VBI in the MPEG stream */ + V4L2_MPEG_STREAM_VBI_FMT_IVTV = 1, /* VBI in private packets, IVTV format */ +}; + +/* MPEG audio controls specific to multiplexed streams */ +#define V4L2_CID_MPEG_AUDIO_SAMPLING_FREQ (V4L2_CID_MPEG_BASE+100) +enum v4l2_mpeg_audio_sampling_freq { + V4L2_MPEG_AUDIO_SAMPLING_FREQ_44100 = 0, + V4L2_MPEG_AUDIO_SAMPLING_FREQ_48000 = 1, + V4L2_MPEG_AUDIO_SAMPLING_FREQ_32000 = 2, +}; +#define V4L2_CID_MPEG_AUDIO_ENCODING (V4L2_CID_MPEG_BASE+101) +enum v4l2_mpeg_audio_encoding { + V4L2_MPEG_AUDIO_ENCODING_LAYER_1 = 0, + V4L2_MPEG_AUDIO_ENCODING_LAYER_2 = 1, + V4L2_MPEG_AUDIO_ENCODING_LAYER_3 = 2, + V4L2_MPEG_AUDIO_ENCODING_AAC = 3, + V4L2_MPEG_AUDIO_ENCODING_AC3 = 4, +}; +#define V4L2_CID_MPEG_AUDIO_L1_BITRATE (V4L2_CID_MPEG_BASE+102) +enum v4l2_mpeg_audio_l1_bitrate { + V4L2_MPEG_AUDIO_L1_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L1_BITRATE_64K = 1, + V4L2_MPEG_AUDIO_L1_BITRATE_96K = 2, + V4L2_MPEG_AUDIO_L1_BITRATE_128K = 3, + V4L2_MPEG_AUDIO_L1_BITRATE_160K = 4, + V4L2_MPEG_AUDIO_L1_BITRATE_192K = 5, + V4L2_MPEG_AUDIO_L1_BITRATE_224K = 6, + V4L2_MPEG_AUDIO_L1_BITRATE_256K = 7, + V4L2_MPEG_AUDIO_L1_BITRATE_288K = 8, + V4L2_MPEG_AUDIO_L1_BITRATE_320K = 9, + V4L2_MPEG_AUDIO_L1_BITRATE_352K = 10, + V4L2_MPEG_AUDIO_L1_BITRATE_384K = 11, + V4L2_MPEG_AUDIO_L1_BITRATE_416K = 12, + V4L2_MPEG_AUDIO_L1_BITRATE_448K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_L2_BITRATE (V4L2_CID_MPEG_BASE+103) +enum v4l2_mpeg_audio_l2_bitrate { + V4L2_MPEG_AUDIO_L2_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L2_BITRATE_48K = 1, + V4L2_MPEG_AUDIO_L2_BITRATE_56K = 2, + V4L2_MPEG_AUDIO_L2_BITRATE_64K = 3, + V4L2_MPEG_AUDIO_L2_BITRATE_80K = 4, + V4L2_MPEG_AUDIO_L2_BITRATE_96K = 5, + V4L2_MPEG_AUDIO_L2_BITRATE_112K = 6, + V4L2_MPEG_AUDIO_L2_BITRATE_128K = 7, + V4L2_MPEG_AUDIO_L2_BITRATE_160K = 8, + V4L2_MPEG_AUDIO_L2_BITRATE_192K = 9, + V4L2_MPEG_AUDIO_L2_BITRATE_224K = 10, + V4L2_MPEG_AUDIO_L2_BITRATE_256K = 11, + V4L2_MPEG_AUDIO_L2_BITRATE_320K = 12, + V4L2_MPEG_AUDIO_L2_BITRATE_384K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_L3_BITRATE (V4L2_CID_MPEG_BASE+104) +enum v4l2_mpeg_audio_l3_bitrate { + V4L2_MPEG_AUDIO_L3_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_L3_BITRATE_40K = 1, + V4L2_MPEG_AUDIO_L3_BITRATE_48K = 2, + V4L2_MPEG_AUDIO_L3_BITRATE_56K = 3, + V4L2_MPEG_AUDIO_L3_BITRATE_64K = 4, + V4L2_MPEG_AUDIO_L3_BITRATE_80K = 5, + V4L2_MPEG_AUDIO_L3_BITRATE_96K = 6, + V4L2_MPEG_AUDIO_L3_BITRATE_112K = 7, + V4L2_MPEG_AUDIO_L3_BITRATE_128K = 8, + V4L2_MPEG_AUDIO_L3_BITRATE_160K = 9, + V4L2_MPEG_AUDIO_L3_BITRATE_192K = 10, + V4L2_MPEG_AUDIO_L3_BITRATE_224K = 11, + V4L2_MPEG_AUDIO_L3_BITRATE_256K = 12, + V4L2_MPEG_AUDIO_L3_BITRATE_320K = 13, +}; +#define V4L2_CID_MPEG_AUDIO_MODE (V4L2_CID_MPEG_BASE+105) +enum v4l2_mpeg_audio_mode { + V4L2_MPEG_AUDIO_MODE_STEREO = 0, + V4L2_MPEG_AUDIO_MODE_JOINT_STEREO = 1, + V4L2_MPEG_AUDIO_MODE_DUAL = 2, + V4L2_MPEG_AUDIO_MODE_MONO = 3, +}; +#define V4L2_CID_MPEG_AUDIO_MODE_EXTENSION (V4L2_CID_MPEG_BASE+106) +enum v4l2_mpeg_audio_mode_extension { + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_4 = 0, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_8 = 1, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_12 = 2, + V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_16 = 3, +}; +#define V4L2_CID_MPEG_AUDIO_EMPHASIS (V4L2_CID_MPEG_BASE+107) +enum v4l2_mpeg_audio_emphasis { + V4L2_MPEG_AUDIO_EMPHASIS_NONE = 0, + V4L2_MPEG_AUDIO_EMPHASIS_50_DIV_15_uS = 1, + V4L2_MPEG_AUDIO_EMPHASIS_CCITT_J17 = 2, +}; +#define V4L2_CID_MPEG_AUDIO_CRC (V4L2_CID_MPEG_BASE+108) +enum v4l2_mpeg_audio_crc { + V4L2_MPEG_AUDIO_CRC_NONE = 0, + V4L2_MPEG_AUDIO_CRC_CRC16 = 1, +}; +#define V4L2_CID_MPEG_AUDIO_MUTE (V4L2_CID_MPEG_BASE+109) +#define V4L2_CID_MPEG_AUDIO_AAC_BITRATE (V4L2_CID_MPEG_BASE+110) +#define V4L2_CID_MPEG_AUDIO_AC3_BITRATE (V4L2_CID_MPEG_BASE+111) +enum v4l2_mpeg_audio_ac3_bitrate { + V4L2_MPEG_AUDIO_AC3_BITRATE_32K = 0, + V4L2_MPEG_AUDIO_AC3_BITRATE_40K = 1, + V4L2_MPEG_AUDIO_AC3_BITRATE_48K = 2, + V4L2_MPEG_AUDIO_AC3_BITRATE_56K = 3, + V4L2_MPEG_AUDIO_AC3_BITRATE_64K = 4, + V4L2_MPEG_AUDIO_AC3_BITRATE_80K = 5, + V4L2_MPEG_AUDIO_AC3_BITRATE_96K = 6, + V4L2_MPEG_AUDIO_AC3_BITRATE_112K = 7, + V4L2_MPEG_AUDIO_AC3_BITRATE_128K = 8, + V4L2_MPEG_AUDIO_AC3_BITRATE_160K = 9, + V4L2_MPEG_AUDIO_AC3_BITRATE_192K = 10, + V4L2_MPEG_AUDIO_AC3_BITRATE_224K = 11, + V4L2_MPEG_AUDIO_AC3_BITRATE_256K = 12, + V4L2_MPEG_AUDIO_AC3_BITRATE_320K = 13, + V4L2_MPEG_AUDIO_AC3_BITRATE_384K = 14, + V4L2_MPEG_AUDIO_AC3_BITRATE_448K = 15, + V4L2_MPEG_AUDIO_AC3_BITRATE_512K = 16, + V4L2_MPEG_AUDIO_AC3_BITRATE_576K = 17, + V4L2_MPEG_AUDIO_AC3_BITRATE_640K = 18, +}; +#define V4L2_CID_MPEG_AUDIO_DEC_PLAYBACK (V4L2_CID_MPEG_BASE+112) +enum v4l2_mpeg_audio_dec_playback { + V4L2_MPEG_AUDIO_DEC_PLAYBACK_AUTO = 0, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_STEREO = 1, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_LEFT = 2, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_RIGHT = 3, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_MONO = 4, + V4L2_MPEG_AUDIO_DEC_PLAYBACK_SWAPPED_STEREO = 5, +}; +#define V4L2_CID_MPEG_AUDIO_DEC_MULTILINGUAL_PLAYBACK (V4L2_CID_MPEG_BASE+113) + +/* MPEG video controls specific to multiplexed streams */ +#define V4L2_CID_MPEG_VIDEO_ENCODING (V4L2_CID_MPEG_BASE+200) +enum v4l2_mpeg_video_encoding { + V4L2_MPEG_VIDEO_ENCODING_MPEG_1 = 0, + V4L2_MPEG_VIDEO_ENCODING_MPEG_2 = 1, + V4L2_MPEG_VIDEO_ENCODING_MPEG_4_AVC = 2, +}; +#define V4L2_CID_MPEG_VIDEO_ASPECT (V4L2_CID_MPEG_BASE+201) +enum v4l2_mpeg_video_aspect { + V4L2_MPEG_VIDEO_ASPECT_1x1 = 0, + V4L2_MPEG_VIDEO_ASPECT_4x3 = 1, + V4L2_MPEG_VIDEO_ASPECT_16x9 = 2, + V4L2_MPEG_VIDEO_ASPECT_221x100 = 3, +}; +#define V4L2_CID_MPEG_VIDEO_B_FRAMES (V4L2_CID_MPEG_BASE+202) +#define V4L2_CID_MPEG_VIDEO_GOP_SIZE (V4L2_CID_MPEG_BASE+203) +#define V4L2_CID_MPEG_VIDEO_GOP_CLOSURE (V4L2_CID_MPEG_BASE+204) +#define V4L2_CID_MPEG_VIDEO_PULLDOWN (V4L2_CID_MPEG_BASE+205) +#define V4L2_CID_MPEG_VIDEO_BITRATE_MODE (V4L2_CID_MPEG_BASE+206) +enum v4l2_mpeg_video_bitrate_mode { + V4L2_MPEG_VIDEO_BITRATE_MODE_VBR = 0, + V4L2_MPEG_VIDEO_BITRATE_MODE_CBR = 1, +}; +#define V4L2_CID_MPEG_VIDEO_BITRATE (V4L2_CID_MPEG_BASE+207) +#define V4L2_CID_MPEG_VIDEO_BITRATE_PEAK (V4L2_CID_MPEG_BASE+208) +#define V4L2_CID_MPEG_VIDEO_TEMPORAL_DECIMATION (V4L2_CID_MPEG_BASE+209) +#define V4L2_CID_MPEG_VIDEO_MUTE (V4L2_CID_MPEG_BASE+210) +#define V4L2_CID_MPEG_VIDEO_MUTE_YUV (V4L2_CID_MPEG_BASE+211) +#define V4L2_CID_MPEG_VIDEO_DECODER_SLICE_INTERFACE (V4L2_CID_MPEG_BASE+212) +#define V4L2_CID_MPEG_VIDEO_DECODER_MPEG4_DEBLOCK_FILTER (V4L2_CID_MPEG_BASE+213) +#define V4L2_CID_MPEG_VIDEO_CYCLIC_INTRA_REFRESH_MB (V4L2_CID_MPEG_BASE+214) +#define V4L2_CID_MPEG_VIDEO_FRAME_RC_ENABLE (V4L2_CID_MPEG_BASE+215) +#define V4L2_CID_MPEG_VIDEO_HEADER_MODE (V4L2_CID_MPEG_BASE+216) +enum v4l2_mpeg_video_header_mode { + V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE = 0, + V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_1ST_FRAME = 1, + V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_I_FRAME = 2, +}; +#define V4L2_CID_MPEG_VIDEO_MAX_REF_PIC (V4L2_CID_MPEG_BASE+217) +#define V4L2_CID_MPEG_VIDEO_MB_RC_ENABLE (V4L2_CID_MPEG_BASE+218) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_BYTES (V4L2_CID_MPEG_BASE+219) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_MB (V4L2_CID_MPEG_BASE+220) +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE (V4L2_CID_MPEG_BASE+221) +enum v4l2_mpeg_video_multi_slice_mode { + V4L2_MPEG_VIDEO_MULTI_SLICE_MODE_SINGLE = 0, + V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_MB = 1, + V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_BYTES = 2, + V4L2_MPEG_VIDEO_MULTI_SLICE_GOB = 3, +}; +#define V4L2_CID_MPEG_VIDEO_VBV_SIZE (V4L2_CID_MPEG_BASE+222) +#define V4L2_CID_MPEG_VIDEO_DEC_PTS (V4L2_CID_MPEG_BASE+223) +#define V4L2_CID_MPEG_VIDEO_DEC_FRAME (V4L2_CID_MPEG_BASE+224) +#define V4L2_CID_MPEG_VIDEO_VBV_DELAY (V4L2_CID_MPEG_BASE+225) +#define V4L2_CID_MPEG_VIDEO_REPEAT_SEQ_HEADER (V4L2_CID_MPEG_BASE+226) +#define V4L2_CID_MPEG_VIDEO_MV_H_SEARCH_RANGE (V4L2_CID_MPEG_BASE+227) +#define V4L2_CID_MPEG_VIDEO_MV_V_SEARCH_RANGE (V4L2_CID_MPEG_BASE+228) +#define V4L2_CID_MPEG_VIDEO_FORCE_KEY_FRAME (V4L2_CID_MPEG_BASE+229) + +#define V4L2_CID_MPEG_VIDEO_H263_I_FRAME_QP (V4L2_CID_MPEG_BASE+300) +#define V4L2_CID_MPEG_VIDEO_H263_P_FRAME_QP (V4L2_CID_MPEG_BASE+301) +#define V4L2_CID_MPEG_VIDEO_H263_B_FRAME_QP (V4L2_CID_MPEG_BASE+302) +#define V4L2_CID_MPEG_VIDEO_H263_MIN_QP (V4L2_CID_MPEG_BASE+303) +#define V4L2_CID_MPEG_VIDEO_H263_MAX_QP (V4L2_CID_MPEG_BASE+304) +#define V4L2_CID_MPEG_VIDEO_H264_I_FRAME_QP (V4L2_CID_MPEG_BASE+350) +#define V4L2_CID_MPEG_VIDEO_H264_P_FRAME_QP (V4L2_CID_MPEG_BASE+351) +#define V4L2_CID_MPEG_VIDEO_H264_B_FRAME_QP (V4L2_CID_MPEG_BASE+352) +#define V4L2_CID_MPEG_VIDEO_H264_MIN_QP (V4L2_CID_MPEG_BASE+353) +#define V4L2_CID_MPEG_VIDEO_H264_MAX_QP (V4L2_CID_MPEG_BASE+354) +#define V4L2_CID_MPEG_VIDEO_H264_8X8_TRANSFORM (V4L2_CID_MPEG_BASE+355) +#define V4L2_CID_MPEG_VIDEO_H264_CPB_SIZE (V4L2_CID_MPEG_BASE+356) +#define V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE (V4L2_CID_MPEG_BASE+357) +enum v4l2_mpeg_video_h264_entropy_mode { + V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CAVLC = 0, + V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_I_PERIOD (V4L2_CID_MPEG_BASE+358) +#define V4L2_CID_MPEG_VIDEO_H264_LEVEL (V4L2_CID_MPEG_BASE+359) +enum v4l2_mpeg_video_h264_level { + V4L2_MPEG_VIDEO_H264_LEVEL_1_0 = 0, + V4L2_MPEG_VIDEO_H264_LEVEL_1B = 1, + V4L2_MPEG_VIDEO_H264_LEVEL_1_1 = 2, + V4L2_MPEG_VIDEO_H264_LEVEL_1_2 = 3, + V4L2_MPEG_VIDEO_H264_LEVEL_1_3 = 4, + V4L2_MPEG_VIDEO_H264_LEVEL_2_0 = 5, + V4L2_MPEG_VIDEO_H264_LEVEL_2_1 = 6, + V4L2_MPEG_VIDEO_H264_LEVEL_2_2 = 7, + V4L2_MPEG_VIDEO_H264_LEVEL_3_0 = 8, + V4L2_MPEG_VIDEO_H264_LEVEL_3_1 = 9, + V4L2_MPEG_VIDEO_H264_LEVEL_3_2 = 10, + V4L2_MPEG_VIDEO_H264_LEVEL_4_0 = 11, + V4L2_MPEG_VIDEO_H264_LEVEL_4_1 = 12, + V4L2_MPEG_VIDEO_H264_LEVEL_4_2 = 13, + V4L2_MPEG_VIDEO_H264_LEVEL_5_0 = 14, + V4L2_MPEG_VIDEO_H264_LEVEL_5_1 = 15, + V4L2_MPEG_VIDEO_H264_LEVEL_5_2 = 16, +#define V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN \ + V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN + V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA (V4L2_CID_MPEG_BASE+360) +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA (V4L2_CID_MPEG_BASE+361) +#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE (V4L2_CID_MPEG_BASE+362) +enum v4l2_mpeg_video_h264_loop_filter_mode { + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_ENABLED = 0, + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED = 1, + V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED_AT_SLICE_BOUNDARY = 2, +}; +#define V4L2_CID_MPEG_VIDEO_H264_PROFILE (V4L2_CID_MPEG_BASE+363) +enum v4l2_mpeg_video_h264_profile { + V4L2_MPEG_VIDEO_H264_PROFILE_BASELINE = 0, + V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_BASELINE = 1, + V4L2_MPEG_VIDEO_H264_PROFILE_MAIN = 2, + V4L2_MPEG_VIDEO_H264_PROFILE_EXTENDED = 3, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH = 4, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10 = 5, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422 = 6, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_PREDICTIVE = 7, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10_INTRA = 8, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422_INTRA = 9, + V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_INTRA = 10, + V4L2_MPEG_VIDEO_H264_PROFILE_CAVLC_444_INTRA = 11, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_BASELINE = 12, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH = 13, + V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH_INTRA = 14, + V4L2_MPEG_VIDEO_H264_PROFILE_STEREO_HIGH = 15, + V4L2_MPEG_VIDEO_H264_PROFILE_MULTIVIEW_HIGH = 16, + V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_HIGH = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_HEIGHT (V4L2_CID_MPEG_BASE+364) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_WIDTH (V4L2_CID_MPEG_BASE+365) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_ENABLE (V4L2_CID_MPEG_BASE+366) +#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_IDC (V4L2_CID_MPEG_BASE+367) +enum v4l2_mpeg_video_h264_vui_sar_idc { + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_UNSPECIFIED = 0, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_1x1 = 1, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_12x11 = 2, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_10x11 = 3, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_16x11 = 4, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_40x33 = 5, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_24x11 = 6, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_20x11 = 7, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_32x11 = 8, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_80x33 = 9, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_18x11 = 10, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_15x11 = 11, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_64x33 = 12, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_160x99 = 13, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_4x3 = 14, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_3x2 = 15, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_2x1 = 16, + V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_EXTENDED = 17, +}; +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FRAME_PACKING (V4L2_CID_MPEG_BASE+368) +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_CURRENT_FRAME_0 (V4L2_CID_MPEG_BASE+369) +#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE (V4L2_CID_MPEG_BASE+370) +enum v4l2_mpeg_video_h264_sei_fp_arrangement_type { + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_CHECKERBOARD = 0, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_COLUMN = 1, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_ROW = 2, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_SIDE_BY_SIDE = 3, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TOP_BOTTOM = 4, + V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TEMPORAL = 5, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO (V4L2_CID_MPEG_BASE+371) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_MAP_TYPE (V4L2_CID_MPEG_BASE+372) +enum v4l2_mpeg_video_h264_fmo_map_type { + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_INTERLEAVED_SLICES = 0, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_SCATTERED_SLICES = 1, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_FOREGROUND_WITH_LEFT_OVER = 2, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_BOX_OUT = 3, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_RASTER_SCAN = 4, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_WIPE_SCAN = 5, + V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_EXPLICIT = 6, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO_SLICE_GROUP (V4L2_CID_MPEG_BASE+373) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_DIRECTION (V4L2_CID_MPEG_BASE+374) +enum v4l2_mpeg_video_h264_fmo_change_dir { + V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_RIGHT = 0, + V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_LEFT = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_RATE (V4L2_CID_MPEG_BASE+375) +#define V4L2_CID_MPEG_VIDEO_H264_FMO_RUN_LENGTH (V4L2_CID_MPEG_BASE+376) +#define V4L2_CID_MPEG_VIDEO_H264_ASO (V4L2_CID_MPEG_BASE+377) +#define V4L2_CID_MPEG_VIDEO_H264_ASO_SLICE_ORDER (V4L2_CID_MPEG_BASE+378) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING (V4L2_CID_MPEG_BASE+379) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_TYPE (V4L2_CID_MPEG_BASE+380) +enum v4l2_mpeg_video_h264_hierarchical_coding_type { + V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_B = 0, + V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_P = 1, +}; +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER (V4L2_CID_MPEG_BASE+381) +#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER_QP (V4L2_CID_MPEG_BASE+382) +#define V4L2_CID_MPEG_VIDEO_MPEG4_I_FRAME_QP (V4L2_CID_MPEG_BASE+400) +#define V4L2_CID_MPEG_VIDEO_MPEG4_P_FRAME_QP (V4L2_CID_MPEG_BASE+401) +#define V4L2_CID_MPEG_VIDEO_MPEG4_B_FRAME_QP (V4L2_CID_MPEG_BASE+402) +#define V4L2_CID_MPEG_VIDEO_MPEG4_MIN_QP (V4L2_CID_MPEG_BASE+403) +#define V4L2_CID_MPEG_VIDEO_MPEG4_MAX_QP (V4L2_CID_MPEG_BASE+404) +#define V4L2_CID_MPEG_VIDEO_MPEG4_LEVEL (V4L2_CID_MPEG_BASE+405) +enum v4l2_mpeg_video_mpeg4_level { + V4L2_MPEG_VIDEO_MPEG4_LEVEL_0 = 0, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_0B = 1, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_1 = 2, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_2 = 3, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_3 = 4, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_3B = 5, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_4 = 6, + V4L2_MPEG_VIDEO_MPEG4_LEVEL_5 = 7, +}; +#define V4L2_CID_MPEG_VIDEO_MPEG4_PROFILE (V4L2_CID_MPEG_BASE+406) +enum v4l2_mpeg_video_mpeg4_profile { + V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE = 0, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_SIMPLE = 1, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_CORE = 2, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE_SCALABLE = 3, + V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_CODING_EFFICIENCY = 4, +}; +#define V4L2_CID_MPEG_VIDEO_MPEG4_QPEL (V4L2_CID_MPEG_BASE+407) + +/* Control IDs for VP8 streams + * Although VP8 is not part of MPEG we add these controls to the MPEG class + * as that class is already handling other video compression standards + */ +#define V4L2_CID_MPEG_VIDEO_VPX_NUM_PARTITIONS (V4L2_CID_MPEG_BASE+500) +enum v4l2_vp8_num_partitions { + V4L2_CID_MPEG_VIDEO_VPX_1_PARTITION = 0, + V4L2_CID_MPEG_VIDEO_VPX_2_PARTITIONS = 1, + V4L2_CID_MPEG_VIDEO_VPX_4_PARTITIONS = 2, + V4L2_CID_MPEG_VIDEO_VPX_8_PARTITIONS = 3, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_IMD_DISABLE_4X4 (V4L2_CID_MPEG_BASE+501) +#define V4L2_CID_MPEG_VIDEO_VPX_NUM_REF_FRAMES (V4L2_CID_MPEG_BASE+502) +enum v4l2_vp8_num_ref_frames { + V4L2_CID_MPEG_VIDEO_VPX_1_REF_FRAME = 0, + V4L2_CID_MPEG_VIDEO_VPX_2_REF_FRAME = 1, + V4L2_CID_MPEG_VIDEO_VPX_3_REF_FRAME = 2, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_LEVEL (V4L2_CID_MPEG_BASE+503) +#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_SHARPNESS (V4L2_CID_MPEG_BASE+504) +#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_REF_PERIOD (V4L2_CID_MPEG_BASE+505) +#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_SEL (V4L2_CID_MPEG_BASE+506) +enum v4l2_vp8_golden_frame_sel { + V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_PREV = 0, + V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_REF_PERIOD = 1, +}; +#define V4L2_CID_MPEG_VIDEO_VPX_MIN_QP (V4L2_CID_MPEG_BASE+507) +#define V4L2_CID_MPEG_VIDEO_VPX_MAX_QP (V4L2_CID_MPEG_BASE+508) +#define V4L2_CID_MPEG_VIDEO_VPX_I_FRAME_QP (V4L2_CID_MPEG_BASE+509) +#define V4L2_CID_MPEG_VIDEO_VPX_P_FRAME_QP (V4L2_CID_MPEG_BASE+510) +#define V4L2_CID_MPEG_VIDEO_VPX_PROFILE (V4L2_CID_MPEG_BASE+511) + +/* MPEG-class control IDs specific to the CX2341x driver as defined by V4L2 */ +#define V4L2_CID_MPEG_CX2341X_BASE (V4L2_CTRL_CLASS_MPEG | 0x1000) +#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+0) +enum v4l2_mpeg_cx2341x_video_spatial_filter_mode { + V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_MANUAL = 0, + V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_AUTO = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+1) +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+2) +enum v4l2_mpeg_cx2341x_video_luma_spatial_filter_type { + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_VERT = 2, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_HV_SEPARABLE = 3, + V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_SYM_NON_SEPARABLE = 4, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+3) +enum v4l2_mpeg_cx2341x_video_chroma_spatial_filter_type { + V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+4) +enum v4l2_mpeg_cx2341x_video_temporal_filter_mode { + V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_MANUAL = 0, + V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_AUTO = 1, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+5) +#define V4L2_CID_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+6) +enum v4l2_mpeg_cx2341x_video_median_filter_type { + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_OFF = 0, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR = 1, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_VERT = 2, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR_VERT = 3, + V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_DIAG = 4, +}; +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+7) +#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+8) +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+9) +#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+10) +#define V4L2_CID_MPEG_CX2341X_STREAM_INSERT_NAV_PACKETS (V4L2_CID_MPEG_CX2341X_BASE+11) + +/* MPEG-class control IDs specific to the Samsung MFC 5.1 driver as defined by V4L2 */ +#define V4L2_CID_MPEG_MFC51_BASE (V4L2_CTRL_CLASS_MPEG | 0x1100) + +#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY (V4L2_CID_MPEG_MFC51_BASE+0) +#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY_ENABLE (V4L2_CID_MPEG_MFC51_BASE+1) +#define V4L2_CID_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE (V4L2_CID_MPEG_MFC51_BASE+2) +enum v4l2_mpeg_mfc51_video_frame_skip_mode { + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_DISABLED = 0, + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_LEVEL_LIMIT = 1, + V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_BUF_LIMIT = 2, +}; +#define V4L2_CID_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE (V4L2_CID_MPEG_MFC51_BASE+3) +enum v4l2_mpeg_mfc51_video_force_frame_type { + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_DISABLED = 0, + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_I_FRAME = 1, + V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_NOT_CODED = 2, +}; +#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING (V4L2_CID_MPEG_MFC51_BASE+4) +#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING_YUV (V4L2_CID_MPEG_MFC51_BASE+5) +#define V4L2_CID_MPEG_MFC51_VIDEO_RC_FIXED_TARGET_BIT (V4L2_CID_MPEG_MFC51_BASE+6) +#define V4L2_CID_MPEG_MFC51_VIDEO_RC_REACTION_COEFF (V4L2_CID_MPEG_MFC51_BASE+7) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_ACTIVITY (V4L2_CID_MPEG_MFC51_BASE+50) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_DARK (V4L2_CID_MPEG_MFC51_BASE+51) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_SMOOTH (V4L2_CID_MPEG_MFC51_BASE+52) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_STATIC (V4L2_CID_MPEG_MFC51_BASE+53) +#define V4L2_CID_MPEG_MFC51_VIDEO_H264_NUM_REF_PIC_FOR_P (V4L2_CID_MPEG_MFC51_BASE+54) + +/* MPEG-class control IDs specific to the msm_vidc driver */ +#define V4L2_CID_MPEG_MSM_VIDC_BASE (V4L2_CTRL_CLASS_MPEG | 0x2000) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PICTYPE_DEC_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+0) +enum v4l2_mpeg_vidc_video_pictype_dec_mode { + V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_OFF = 0, + V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_ON = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_KEEP_ASPECT_RATIO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+1) + +#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+2) +enum v4l2_mpeg_vidc_video_stream_format { + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_STARTCODES = 0, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_NAL_PER_BUFFER = 1, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_BYTE_LENGTH = 2, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_TWO_BYTE_LENGTH = 3, + V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_FOUR_BYTE_LENGTH = 4, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_OUTPUT_ORDER (V4L2_CID_MPEG_MSM_VIDC_BASE+3) +enum v4l2_mpeg_vidc_video_output_order { + V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DISPLAY = 0, + V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DECODE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_RATE (V4L2_CID_MPEG_MSM_VIDC_BASE+4) +#define V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD (V4L2_CID_MPEG_MSM_VIDC_BASE+5) +#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+6) +#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+7) +#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_IFRAME (V4L2_CID_MPEG_MSM_VIDC_BASE+8) + +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL (V4L2_CID_MPEG_MSM_VIDC_BASE+9) +enum v4l2_mpeg_vidc_video_rate_control { + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_OFF = 0, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_VFR = 1, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR = 2, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_VFR = 3, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_CFR = 4, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR = 5, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR = 6, + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CQ = 7, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR \ + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR \ + V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR + +#define V4L2_CID_MPEG_VIDC_VIDEO_ROTATION (V4L2_CID_MPEG_MSM_VIDC_BASE+10) +enum v4l2_mpeg_vidc_video_rotation { + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_90 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_180 = 2, + V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_270 = 3, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+11) +enum v4l2_mpeg_vidc_h264_cabac_model { + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0 = 0, + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_1 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_2 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+12) +enum v4l2_mpeg_vidc_video_intra_refresh_mode { + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC = 1, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_RANDOM = 2, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_ADAPTIVE = 3, + V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC_ADAPTIVE = 4, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_IR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE+13) + +#define V4L2_CID_MPEG_VIDC_VIDEO_AU_DELIMITER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 14) +enum v4l2_mpeg_vidc_video_au_delimiter { + V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_ENABLED = 1 +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 15) +enum v4l2_mpeg_vidc_video_sync_frame_decode { + V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_ENABLE = 1 +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE (V4L2_CID_MPEG_MSM_VIDC_BASE+16) +#define V4L2_CID_MPEG_VIDC_VIDEO_EXTRADATA \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 17) +enum v4l2_mpeg_vidc_extradata { + V4L2_MPEG_VIDC_EXTRADATA_NONE = 0, + V4L2_MPEG_VIDC_EXTRADATA_MB_QUANTIZATION = 1, + V4L2_MPEG_VIDC_EXTRADATA_INTERLACE_VIDEO = 2, + V4L2_MPEG_VIDC_EXTRADATA_VC1_FRAMEDISP = 3, + V4L2_MPEG_VIDC_EXTRADATA_VC1_SEQDISP = 4, + V4L2_MPEG_VIDC_EXTRADATA_TIMESTAMP = 5, + V4L2_MPEG_VIDC_EXTRADATA_S3D_FRAME_PACKING = 6, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_RATE = 7, + V4L2_MPEG_VIDC_EXTRADATA_PANSCAN_WINDOW = 8, + V4L2_MPEG_VIDC_EXTRADATA_RECOVERY_POINT_SEI = 9, + V4L2_MPEG_VIDC_EXTRADATA_MULTISLICE_INFO = 10, + V4L2_MPEG_VIDC_EXTRADATA_NUM_CONCEALED_MB = 11, + V4L2_MPEG_VIDC_EXTRADATA_METADATA_FILLER = 12, + V4L2_MPEG_VIDC_EXTRADATA_INPUT_CROP = 13, + V4L2_MPEG_VIDC_EXTRADATA_DIGITAL_ZOOM = 14, + V4L2_MPEG_VIDC_EXTRADATA_ASPECT_RATIO = 15, + V4L2_MPEG_VIDC_EXTRADATA_MPEG2_SEQDISP = 16, + V4L2_MPEG_VIDC_EXTRADATA_STREAM_USERDATA = 17, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_QP = 18, + V4L2_MPEG_VIDC_EXTRADATA_FRAME_BITS_INFO = 19, + V4L2_MPEG_VIDC_EXTRADATA_LTR = 20, + V4L2_MPEG_VIDC_EXTRADATA_METADATA_MBI = 21, + V4L2_MPEG_VIDC_EXTRADATA_VQZIP_SEI = 22, + V4L2_MPEG_VIDC_EXTRADATA_YUV_STATS = 23, + V4L2_MPEG_VIDC_EXTRADATA_ROI_QP = 24, +#define V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP \ + V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP + V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP = 25, +#define V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI \ + V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI + V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI = 26, +#define V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI \ + V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI + V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI = 27, +#define V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO \ + V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO + V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO = 28, +#define V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY \ + V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY + V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY = 29, +#define V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE \ + V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE + V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE = 30, +#define V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO \ + V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO + V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO = 31, +#define V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP \ + V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP + V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP = 32, +}; + +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_DELIVERY_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 18) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 19) +enum v4l2_mpeg_vidc_video_vui_timing_info { + V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_PROFILE_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 20) +enum v4l2_mpeg_vidc_video_vp8_profile_level { + V4L2_MPEG_VIDC_VIDEO_VP8_UNUSED, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_0, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_1, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_2, + V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_3, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 21) +enum v4l2_mpeg_vidc_video_preserve_text_quality { + V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 22) +enum v4l2_mpeg_vidc_video_decoder_multi_stream { + V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_PRIMARY = 0, + V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_SECONDARY = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE+23) +enum v4l2_mpeg_vidc_video_mpeg2_level { + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_0 = 0, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_2 = 2, + V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_3 = 3, +}; +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_PROFILE (V4L2_CID_MPEG_MSM_VIDC_BASE+24) +enum v4l2_mpeg_vidc_video_mpeg2_profile { + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SIMPLE = 0, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_MAIN = 1, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_422 = 2, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SNR_SCALABLE = 3, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SPATIAL_SCALABLE = 4, + V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_HIGH = 5, +}; + +enum v4l2_mpeg_vidc_video_mvc_layout { + V4L2_MPEG_VIDC_VIDEO_MVC_SEQUENTIAL = 0, + V4L2_MPEG_VIDC_VIDEO_MVC_TOP_BOTTOM = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 25) + +#define V4L2_CID_MPEG_VIDC_VIDEO_LTRMODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 26) + +enum v4l2_mpeg_vidc_video_ltrmode { + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_MANUAL = 1, + V4L2_MPEG_VIDC_VIDEO_LTR_MODE_PERIODIC = 2 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_LTRCOUNT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 27) + +#define V4L2_CID_MPEG_VIDC_VIDEO_USELTRFRAME \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 28) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MARKLTRFRAME \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 29) + +#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_P_NUM_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 30) + +#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_OUTPUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+31) +enum v4l2_mpeg_vidc_video_alloc_mode_type { + V4L2_MPEG_VIDC_VIDEO_STATIC = 0, + V4L2_MPEG_VIDC_VIDEO_RING = 1, + V4L2_MPEG_VIDC_VIDEO_DYNAMIC = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 32) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 33) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_X_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 34) + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 35) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 36) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_Y_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 37) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 38) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BUFFER_SIZE_LIMIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 39) + +enum vl42_mpeg_vidc_video_vpx_error_resilience { + V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_ENABLED = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 40) +enum v4l2_mpeg_video_hevc_profile { + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN = 0, + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN10 = 1, + V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN_STILL_PIC = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 41) +enum v4l2_mpeg_video_hevc_level { + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_1 = 0, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2 = 2, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2 = 3, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2_1 = 4, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2_1 = 5, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3 = 6, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3 = 7, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3_1 = 8, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3_1 = 9, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4 = 10, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4 = 11, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4_1 = 12, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4_1 = 13, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5 = 14, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5 = 15, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_1 = 16, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_1 = 17, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_2 = 18, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_2 = 19, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6 = 20, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6 = 21, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_1 = 22, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_1 = 23, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_2 = 24, + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_2 = 25, +#define V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN \ + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN + V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN = 26, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_B_NUM_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 42) + +#define V4L2_CID_MPEG_VIDC_VIDEO_HYBRID_HIERP_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 43) + +#define V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 44) + +enum v4l2_mpeg_vidc_video_dpb_color_format { + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_NONE = 0, + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_UBWC = 1, + V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_TP10_UBWC = 2 +}; + +#define V4L2_CID_VIDC_QBUF_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 45) +enum v4l2_vidc_qbuf_mode { + V4L2_VIDC_QBUF_STANDARD = 0, + V4L2_VIDC_QBUF_BATCHED = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MAX_HIERP_LAYERS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 46) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BASELAYER_ID \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 47) + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_WIDTH \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 48) + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_HEIGHT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 49) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 50) + +enum v4l2_mpeg_vidc_video_vqzip_sei_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VENC_PARAM_LAYER_BITRATE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 51) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 52) + +enum v4l2_mpeg_vidc_video_priority { + V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_ENABLE = 0, + V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_OPERATING_RATE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 53) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_TYPE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 54) + +enum v4l2_mpeg_vidc_video_venc_bitrate_type_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 55) + +enum v4l2_cid_mpeg_vidc_video_vpe_csc_type_enable { + V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_ENABLE = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 56) + +enum v4l2_mpeg_vidc_video_lowlatency_mode { + V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_WIDTH \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 57) + +#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_HEIGHT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 58) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 59) +enum v4l2_mpeg_vidc_video_h264_transform_8x8 { + V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_DISABLE = 0, + V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_COLOR_SPACE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 60) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 61) + +enum v4l2_cid_mpeg_vidc_video_full_range { + V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_DISABLE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TRANSFER_CHARS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 62) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MATRIX_COEFFS \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 63) + +#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_TYPE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 64) + +#define V4L2_CID_MPEG_VIDC_VIDEO_LAYER_ID \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 65) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 66) +enum v4l2_mpeg_vidc_video_vp9_profile { + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_UNUSED = 0, + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P0 = 1, + V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P2_10 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 67) +enum v4l2_mpeg_vidc_video_vp9_level { + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_UNUSED = 0, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_1 = 1, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_11 = 2, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_2 = 3, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_21 = 4, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_3 = 5, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_31 = 6, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_4 = 7, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_41 = 8, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_5 = 9, + V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_51 = 10, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MB_ERROR_MAP_REPORTING \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 68) +#define V4L2_CID_MPEG_VIDC_VIDEO_CONTINUE_DATA_TRANSFER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 69) + +#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_INPUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 70) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_ASSEMBLY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 71) +enum v4l2_mpeg_vidc_video_assembly { + V4L2_MPEG_VIDC_FRAME_ASSEMBLY_DISABLE = 0, + V4L2_MPEG_VIDC_FRAME_ASSEMBLY_ENABLE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_H263_PROFILE\ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 72) +enum v4l2_mpeg_vidc_video_h263_profile { + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BASELINE = 0, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_H320CODING = 1, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BACKWARDCOMPATIBLE = 2, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV2 = 3, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV3 = 4, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHCOMPRESSION = 5, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERNET = 6, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERLACE = 7, + V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHLATENCY = 8, +}; + +#define V4L2_CID_MPEG_VIDEO_MIN_QP_PACKED \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 97) +#define V4L2_CID_MPEG_VIDEO_MAX_QP_PACKED \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 98) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 99) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 100) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 101) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 102) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 103) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MIN \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 104) +#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 105) +#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 106) +#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MAX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 107) +#define V4L2_CID_MPEG_VIDC_VIDEO_QP_MASK \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 108) + +enum v4l2_mpeg_vidc_video_venc_iframesize_type { + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_DEFAULT, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_MEDIUM, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_HUGE, + V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_UNLIMITED, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_8BIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 109) +#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_10BIT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 110) + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PROFILE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 111) + +enum v4l2_mpeg_vidc_video_tme_profile { + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_0 = 0, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_1 = 1, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_2 = 2, + V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_3 = 3, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 112) + +enum v4l2_mpeg_vidc_video_tme_level { + V4L2_MPEG_VIDC_VIDEO_TME_LEVEL_INTEGER = 0, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PAYLOAD_VERSION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 113) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_CUSTOM_MATRIX \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 114) + +#define V4L2_CID_MPEG_VIDC_VIDEO_FLIP (V4L2_CID_MPEG_MSM_VIDC_BASE + 115) +enum v4l2_mpeg_vidc_video_flip { + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_NONE = 0, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_HORI = 1, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_VERT = 2, + V4L2_CID_MPEG_VIDC_VIDEO_FLIP_BOTH = 3, +}; + +/* HDR SEI INFO related control IDs and definitions*/ +#define V4L2_MPEG_VIDC_VENC_HDR_INFO_ENABLED 1 +#define V4L2_MPEG_VIDC_VENC_HDR_INFO_DISABLED 0 + +#define V4L2_CID_MPEG_VIDC_VENC_HDR_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 116) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_00 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 117) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_01 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 118) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_10 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 119) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_11 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 120) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_20 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 121) +#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_21 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 122) +#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_X \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 123) +#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_Y \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 124) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_DISP_LUM \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 125) +#define V4L2_CID_MPEG_VIDC_VENC_MIN_DISP_LUM \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 126) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_CLL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 127) +#define V4L2_CID_MPEG_VIDC_VENC_MAX_FLL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 128) + +#define V4L2_CID_MPEG_VIDC_SET_PERF_LEVEL \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 129) +enum v4l2_mpeg_vidc_perf_level { + V4L2_CID_MPEG_VIDC_PERF_LEVEL_NOMINAL = 0, + V4L2_CID_MPEG_VIDC_PERF_LEVEL_PERFORMANCE = 1, + V4L2_CID_MPEG_VIDC_PERF_LEVEL_TURBO = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 130) +#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_REF (V4L2_CID_MPEG_MSM_VIDC_BASE + 131) +#define V4L2_CID_MPEG_VIDC_VIDEO_CIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 132) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 135) + +#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_GOB \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 136) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 137) +enum v4l2_mpeg_vidc_video_h264_vui_bitstream_restrict { + V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 138) +enum v4l2_mpeg_vidc_video_deinterlace { + V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_DISABLED = 0, + V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_ENABLED = 1 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG4_TIME_RESOLUTION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 139) + +#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_SEQ_HEADER \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 140) + +#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 141) +enum v4l2_mpeg_vidc_video_rate_control_timestamp_mode { + V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_HONOR = 0, + V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_IGNORE = 1, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 142) +enum vl42_mpeg_vidc_video_enable_initial_qp { + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_IFRAME = 0x1, + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_PFRAME = 0x2, + V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_BFRAME = 0x4, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_I_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 143) + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_P_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 144) + +#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_B_FRAME_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 145) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 146) + +#define V4L2_CID_MPEG_VIDC_VIDEO_PERF_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 147) +enum v4l2_mpeg_vidc_video_perf_mode { + V4L2_MPEG_VIDC_VIDEO_PERF_MAX_QUALITY = 1, + V4L2_MPEG_VIDC_VIDEO_PERF_POWER_SAVE = 2 +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_MBI_STATISTICS_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 148) + +#define V4L2_CID_MPEG_VIDC_VIDEO_CONFIG_QP \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 149) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H264_PIC_ORDER_CNT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 150) + +#define V4L2_CID_MPEG_VIDC_VIDEO_SCS_THRESHOLD \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 151) + +#define V4L2_CID_MPEG_VIDC_VIDEO_MVC_BUFFER_LAYOUT \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 152) + + +#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE_SCALING_THRESHOLD \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 153) + +#define V4L2_CID_MPEG_VIDC_VIDEO_NON_SECURE_OUTPUT2 \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 154) + +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MIN_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 155) +#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MAX_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 156) + +#define V4L2_CID_MPEG_VIDC_VIDEO_H263_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE + 157) +enum v4l2_mpeg_vidc_video_h263_level { + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_1_0 = 0, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_2_0 = 1, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_3_0 = 2, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_0 = 3, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_5 = 4, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_5_0 = 5, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_6_0 = 6, + V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_7_0 = 7, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_POST_LOOP_DEBLOCKER_MODE \ + (V4L2_CID_MPEG_MSM_VIDC_BASE + 158) + + +#define V4L2_CID_MPEG_VIDC_VIDEO_DIVX_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+159) + +enum v4l2_mpeg_vidc_video_divx_format_type { + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_4 = 0, + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_5 = 1, + V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_6 = 2, +}; + +#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_QUALITY \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+160) + +#define V4L2_CID_MPEG_VIDC_IMG_GRID_DIMENSION \ + (V4L2_CID_MPEG_MSM_VIDC_BASE+161) + +enum v4l2_mpeg_vidc_video_mbi_statistics_mode { + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_DEFAULT = 0, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_1 = 1, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_2 = 2, + V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_3 = 3, +}; + +enum vl42_mpeg_vidc_video_h264_svc_nal { + V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_DISABLED = 0, + V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_ENABLED = 1, +}; + +enum v4l2_mpeg_vidc_video_h264_vui_timing_info { + V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_DISABLED = 0, + V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_ENABLED = 1 +}; + +/* Camera class control IDs */ + +#define V4L2_CID_CAMERA_CLASS_BASE (V4L2_CTRL_CLASS_CAMERA | 0x900) +#define V4L2_CID_CAMERA_CLASS (V4L2_CTRL_CLASS_CAMERA | 1) + +#define V4L2_CID_EXPOSURE_AUTO (V4L2_CID_CAMERA_CLASS_BASE+1) +enum v4l2_exposure_auto_type { + V4L2_EXPOSURE_AUTO = 0, + V4L2_EXPOSURE_MANUAL = 1, + V4L2_EXPOSURE_SHUTTER_PRIORITY = 2, + V4L2_EXPOSURE_APERTURE_PRIORITY = 3 +}; +#define V4L2_CID_EXPOSURE_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+2) +#define V4L2_CID_EXPOSURE_AUTO_PRIORITY (V4L2_CID_CAMERA_CLASS_BASE+3) + +#define V4L2_CID_PAN_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+4) +#define V4L2_CID_TILT_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+5) +#define V4L2_CID_PAN_RESET (V4L2_CID_CAMERA_CLASS_BASE+6) +#define V4L2_CID_TILT_RESET (V4L2_CID_CAMERA_CLASS_BASE+7) + +#define V4L2_CID_PAN_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+8) +#define V4L2_CID_TILT_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+9) + +#define V4L2_CID_FOCUS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+10) +#define V4L2_CID_FOCUS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+11) +#define V4L2_CID_FOCUS_AUTO (V4L2_CID_CAMERA_CLASS_BASE+12) + +#define V4L2_CID_ZOOM_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+13) +#define V4L2_CID_ZOOM_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+14) +#define V4L2_CID_ZOOM_CONTINUOUS (V4L2_CID_CAMERA_CLASS_BASE+15) + +#define V4L2_CID_PRIVACY (V4L2_CID_CAMERA_CLASS_BASE+16) + +#define V4L2_CID_IRIS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+17) +#define V4L2_CID_IRIS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+18) + +#define V4L2_CID_AUTO_EXPOSURE_BIAS (V4L2_CID_CAMERA_CLASS_BASE+19) + +#define V4L2_CID_AUTO_N_PRESET_WHITE_BALANCE (V4L2_CID_CAMERA_CLASS_BASE+20) +enum v4l2_auto_n_preset_white_balance { + V4L2_WHITE_BALANCE_MANUAL = 0, + V4L2_WHITE_BALANCE_AUTO = 1, + V4L2_WHITE_BALANCE_INCANDESCENT = 2, + V4L2_WHITE_BALANCE_FLUORESCENT = 3, + V4L2_WHITE_BALANCE_FLUORESCENT_H = 4, + V4L2_WHITE_BALANCE_HORIZON = 5, + V4L2_WHITE_BALANCE_DAYLIGHT = 6, + V4L2_WHITE_BALANCE_FLASH = 7, + V4L2_WHITE_BALANCE_CLOUDY = 8, + V4L2_WHITE_BALANCE_SHADE = 9, +}; + +#define V4L2_CID_WIDE_DYNAMIC_RANGE (V4L2_CID_CAMERA_CLASS_BASE+21) +#define V4L2_CID_IMAGE_STABILIZATION (V4L2_CID_CAMERA_CLASS_BASE+22) + +#define V4L2_CID_ISO_SENSITIVITY (V4L2_CID_CAMERA_CLASS_BASE+23) +#define V4L2_CID_ISO_SENSITIVITY_AUTO (V4L2_CID_CAMERA_CLASS_BASE+24) +enum v4l2_iso_sensitivity_auto_type { + V4L2_ISO_SENSITIVITY_MANUAL = 0, + V4L2_ISO_SENSITIVITY_AUTO = 1, +}; + +#define V4L2_CID_EXPOSURE_METERING (V4L2_CID_CAMERA_CLASS_BASE+25) +enum v4l2_exposure_metering { + V4L2_EXPOSURE_METERING_AVERAGE = 0, + V4L2_EXPOSURE_METERING_CENTER_WEIGHTED = 1, + V4L2_EXPOSURE_METERING_SPOT = 2, + V4L2_EXPOSURE_METERING_MATRIX = 3, +}; + +#define V4L2_CID_SCENE_MODE (V4L2_CID_CAMERA_CLASS_BASE+26) +enum v4l2_scene_mode { + V4L2_SCENE_MODE_NONE = 0, + V4L2_SCENE_MODE_BACKLIGHT = 1, + V4L2_SCENE_MODE_BEACH_SNOW = 2, + V4L2_SCENE_MODE_CANDLE_LIGHT = 3, + V4L2_SCENE_MODE_DAWN_DUSK = 4, + V4L2_SCENE_MODE_FALL_COLORS = 5, + V4L2_SCENE_MODE_FIREWORKS = 6, + V4L2_SCENE_MODE_LANDSCAPE = 7, + V4L2_SCENE_MODE_NIGHT = 8, + V4L2_SCENE_MODE_PARTY_INDOOR = 9, + V4L2_SCENE_MODE_PORTRAIT = 10, + V4L2_SCENE_MODE_SPORTS = 11, + V4L2_SCENE_MODE_SUNSET = 12, + V4L2_SCENE_MODE_TEXT = 13, +}; + +#define V4L2_CID_3A_LOCK (V4L2_CID_CAMERA_CLASS_BASE+27) +#define V4L2_LOCK_EXPOSURE (1 << 0) +#define V4L2_LOCK_WHITE_BALANCE (1 << 1) +#define V4L2_LOCK_FOCUS (1 << 2) + +#define V4L2_CID_AUTO_FOCUS_START (V4L2_CID_CAMERA_CLASS_BASE+28) +#define V4L2_CID_AUTO_FOCUS_STOP (V4L2_CID_CAMERA_CLASS_BASE+29) +#define V4L2_CID_AUTO_FOCUS_STATUS (V4L2_CID_CAMERA_CLASS_BASE+30) +#define V4L2_AUTO_FOCUS_STATUS_IDLE (0 << 0) +#define V4L2_AUTO_FOCUS_STATUS_BUSY (1 << 0) +#define V4L2_AUTO_FOCUS_STATUS_REACHED (1 << 1) +#define V4L2_AUTO_FOCUS_STATUS_FAILED (1 << 2) + +#define V4L2_CID_AUTO_FOCUS_RANGE (V4L2_CID_CAMERA_CLASS_BASE+31) +enum v4l2_auto_focus_range { + V4L2_AUTO_FOCUS_RANGE_AUTO = 0, + V4L2_AUTO_FOCUS_RANGE_NORMAL = 1, + V4L2_AUTO_FOCUS_RANGE_MACRO = 2, + V4L2_AUTO_FOCUS_RANGE_INFINITY = 3, +}; + +#define V4L2_CID_PAN_SPEED (V4L2_CID_CAMERA_CLASS_BASE+32) +#define V4L2_CID_TILT_SPEED (V4L2_CID_CAMERA_CLASS_BASE+33) + +/* FM Modulator class control IDs */ + +#define V4L2_CID_FM_TX_CLASS_BASE (V4L2_CTRL_CLASS_FM_TX | 0x900) +#define V4L2_CID_FM_TX_CLASS (V4L2_CTRL_CLASS_FM_TX | 1) + +#define V4L2_CID_RDS_TX_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 1) +#define V4L2_CID_RDS_TX_PI (V4L2_CID_FM_TX_CLASS_BASE + 2) +#define V4L2_CID_RDS_TX_PTY (V4L2_CID_FM_TX_CLASS_BASE + 3) +#define V4L2_CID_RDS_TX_PS_NAME (V4L2_CID_FM_TX_CLASS_BASE + 5) +#define V4L2_CID_RDS_TX_RADIO_TEXT (V4L2_CID_FM_TX_CLASS_BASE + 6) +#define V4L2_CID_RDS_TX_MONO_STEREO (V4L2_CID_FM_TX_CLASS_BASE + 7) +#define V4L2_CID_RDS_TX_ARTIFICIAL_HEAD (V4L2_CID_FM_TX_CLASS_BASE + 8) +#define V4L2_CID_RDS_TX_COMPRESSED (V4L2_CID_FM_TX_CLASS_BASE + 9) +#define V4L2_CID_RDS_TX_DYNAMIC_PTY (V4L2_CID_FM_TX_CLASS_BASE + 10) +#define V4L2_CID_RDS_TX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_TX_CLASS_BASE + 11) +#define V4L2_CID_RDS_TX_TRAFFIC_PROGRAM (V4L2_CID_FM_TX_CLASS_BASE + 12) +#define V4L2_CID_RDS_TX_MUSIC_SPEECH (V4L2_CID_FM_TX_CLASS_BASE + 13) +#define V4L2_CID_RDS_TX_ALT_FREQS_ENABLE (V4L2_CID_FM_TX_CLASS_BASE + 14) +#define V4L2_CID_RDS_TX_ALT_FREQS (V4L2_CID_FM_TX_CLASS_BASE + 15) + +#define V4L2_CID_AUDIO_LIMITER_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 64) +#define V4L2_CID_AUDIO_LIMITER_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 65) +#define V4L2_CID_AUDIO_LIMITER_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 66) + +#define V4L2_CID_AUDIO_COMPRESSION_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 80) +#define V4L2_CID_AUDIO_COMPRESSION_GAIN (V4L2_CID_FM_TX_CLASS_BASE + 81) +#define V4L2_CID_AUDIO_COMPRESSION_THRESHOLD (V4L2_CID_FM_TX_CLASS_BASE + 82) +#define V4L2_CID_AUDIO_COMPRESSION_ATTACK_TIME (V4L2_CID_FM_TX_CLASS_BASE + 83) +#define V4L2_CID_AUDIO_COMPRESSION_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 84) + +#define V4L2_CID_PILOT_TONE_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 96) +#define V4L2_CID_PILOT_TONE_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 97) +#define V4L2_CID_PILOT_TONE_FREQUENCY (V4L2_CID_FM_TX_CLASS_BASE + 98) + +#define V4L2_CID_TUNE_PREEMPHASIS (V4L2_CID_FM_TX_CLASS_BASE + 112) +enum v4l2_preemphasis { + V4L2_PREEMPHASIS_DISABLED = 0, + V4L2_PREEMPHASIS_50_uS = 1, + V4L2_PREEMPHASIS_75_uS = 2, +}; +#define V4L2_CID_TUNE_POWER_LEVEL (V4L2_CID_FM_TX_CLASS_BASE + 113) +#define V4L2_CID_TUNE_ANTENNA_CAPACITOR (V4L2_CID_FM_TX_CLASS_BASE + 114) + + +/* Flash and privacy (indicator) light controls */ + +#define V4L2_CID_FLASH_CLASS_BASE (V4L2_CTRL_CLASS_FLASH | 0x900) +#define V4L2_CID_FLASH_CLASS (V4L2_CTRL_CLASS_FLASH | 1) + +#define V4L2_CID_FLASH_LED_MODE (V4L2_CID_FLASH_CLASS_BASE + 1) +enum v4l2_flash_led_mode { + V4L2_FLASH_LED_MODE_NONE, + V4L2_FLASH_LED_MODE_FLASH, + V4L2_FLASH_LED_MODE_TORCH, +}; + +#define V4L2_CID_FLASH_STROBE_SOURCE (V4L2_CID_FLASH_CLASS_BASE + 2) +enum v4l2_flash_strobe_source { + V4L2_FLASH_STROBE_SOURCE_SOFTWARE, + V4L2_FLASH_STROBE_SOURCE_EXTERNAL, +}; + +#define V4L2_CID_FLASH_STROBE (V4L2_CID_FLASH_CLASS_BASE + 3) +#define V4L2_CID_FLASH_STROBE_STOP (V4L2_CID_FLASH_CLASS_BASE + 4) +#define V4L2_CID_FLASH_STROBE_STATUS (V4L2_CID_FLASH_CLASS_BASE + 5) + +#define V4L2_CID_FLASH_TIMEOUT (V4L2_CID_FLASH_CLASS_BASE + 6) +#define V4L2_CID_FLASH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 7) +#define V4L2_CID_FLASH_TORCH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 8) +#define V4L2_CID_FLASH_INDICATOR_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 9) + +#define V4L2_CID_FLASH_FAULT (V4L2_CID_FLASH_CLASS_BASE + 10) +#define V4L2_FLASH_FAULT_OVER_VOLTAGE (1 << 0) +#define V4L2_FLASH_FAULT_TIMEOUT (1 << 1) +#define V4L2_FLASH_FAULT_OVER_TEMPERATURE (1 << 2) +#define V4L2_FLASH_FAULT_SHORT_CIRCUIT (1 << 3) +#define V4L2_FLASH_FAULT_OVER_CURRENT (1 << 4) +#define V4L2_FLASH_FAULT_INDICATOR (1 << 5) +#define V4L2_FLASH_FAULT_UNDER_VOLTAGE (1 << 6) +#define V4L2_FLASH_FAULT_INPUT_VOLTAGE (1 << 7) +#define V4L2_FLASH_FAULT_LED_OVER_TEMPERATURE (1 << 8) + +#define V4L2_CID_FLASH_CHARGE (V4L2_CID_FLASH_CLASS_BASE + 11) +#define V4L2_CID_FLASH_READY (V4L2_CID_FLASH_CLASS_BASE + 12) + + +/* JPEG-class control IDs */ + +#define V4L2_CID_JPEG_CLASS_BASE (V4L2_CTRL_CLASS_JPEG | 0x900) +#define V4L2_CID_JPEG_CLASS (V4L2_CTRL_CLASS_JPEG | 1) + +#define V4L2_CID_JPEG_CHROMA_SUBSAMPLING (V4L2_CID_JPEG_CLASS_BASE + 1) +enum v4l2_jpeg_chroma_subsampling { + V4L2_JPEG_CHROMA_SUBSAMPLING_444 = 0, + V4L2_JPEG_CHROMA_SUBSAMPLING_422 = 1, + V4L2_JPEG_CHROMA_SUBSAMPLING_420 = 2, + V4L2_JPEG_CHROMA_SUBSAMPLING_411 = 3, + V4L2_JPEG_CHROMA_SUBSAMPLING_410 = 4, + V4L2_JPEG_CHROMA_SUBSAMPLING_GRAY = 5, +}; +#define V4L2_CID_JPEG_RESTART_INTERVAL (V4L2_CID_JPEG_CLASS_BASE + 2) +#define V4L2_CID_JPEG_COMPRESSION_QUALITY (V4L2_CID_JPEG_CLASS_BASE + 3) + +#define V4L2_CID_JPEG_ACTIVE_MARKER (V4L2_CID_JPEG_CLASS_BASE + 4) +#define V4L2_JPEG_ACTIVE_MARKER_APP0 (1 << 0) +#define V4L2_JPEG_ACTIVE_MARKER_APP1 (1 << 1) +#define V4L2_JPEG_ACTIVE_MARKER_COM (1 << 16) +#define V4L2_JPEG_ACTIVE_MARKER_DQT (1 << 17) +#define V4L2_JPEG_ACTIVE_MARKER_DHT (1 << 18) + + +/* Image source controls */ +#define V4L2_CID_IMAGE_SOURCE_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_SOURCE | 0x900) +#define V4L2_CID_IMAGE_SOURCE_CLASS (V4L2_CTRL_CLASS_IMAGE_SOURCE | 1) + +#define V4L2_CID_VBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 1) +#define V4L2_CID_HBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 2) +#define V4L2_CID_ANALOGUE_GAIN (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 3) +#define V4L2_CID_TEST_PATTERN_RED (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 4) +#define V4L2_CID_TEST_PATTERN_GREENR (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 5) +#define V4L2_CID_TEST_PATTERN_BLUE (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 6) +#define V4L2_CID_TEST_PATTERN_GREENB (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 7) + + +/* Image processing controls */ + +#define V4L2_CID_IMAGE_PROC_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_PROC | 0x900) +#define V4L2_CID_IMAGE_PROC_CLASS (V4L2_CTRL_CLASS_IMAGE_PROC | 1) + +#define V4L2_CID_LINK_FREQ (V4L2_CID_IMAGE_PROC_CLASS_BASE + 1) +#define V4L2_CID_PIXEL_RATE (V4L2_CID_IMAGE_PROC_CLASS_BASE + 2) +#define V4L2_CID_TEST_PATTERN (V4L2_CID_IMAGE_PROC_CLASS_BASE + 3) + + +/* DV-class control IDs defined by V4L2 */ +#define V4L2_CID_DV_CLASS_BASE (V4L2_CTRL_CLASS_DV | 0x900) +#define V4L2_CID_DV_CLASS (V4L2_CTRL_CLASS_DV | 1) + +#define V4L2_CID_DV_TX_HOTPLUG (V4L2_CID_DV_CLASS_BASE + 1) +#define V4L2_CID_DV_TX_RXSENSE (V4L2_CID_DV_CLASS_BASE + 2) +#define V4L2_CID_DV_TX_EDID_PRESENT (V4L2_CID_DV_CLASS_BASE + 3) +#define V4L2_CID_DV_TX_MODE (V4L2_CID_DV_CLASS_BASE + 4) +enum v4l2_dv_tx_mode { + V4L2_DV_TX_MODE_DVI_D = 0, + V4L2_DV_TX_MODE_HDMI = 1, +}; +#define V4L2_CID_DV_TX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 5) +enum v4l2_dv_rgb_range { + V4L2_DV_RGB_RANGE_AUTO = 0, + V4L2_DV_RGB_RANGE_LIMITED = 1, + V4L2_DV_RGB_RANGE_FULL = 2, +}; + +#define V4L2_CID_DV_TX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 6) +enum v4l2_dv_it_content_type { + V4L2_DV_IT_CONTENT_TYPE_GRAPHICS = 0, + V4L2_DV_IT_CONTENT_TYPE_PHOTO = 1, + V4L2_DV_IT_CONTENT_TYPE_CINEMA = 2, + V4L2_DV_IT_CONTENT_TYPE_GAME = 3, + V4L2_DV_IT_CONTENT_TYPE_NO_ITC = 4, +}; + +#define V4L2_CID_DV_RX_POWER_PRESENT (V4L2_CID_DV_CLASS_BASE + 100) +#define V4L2_CID_DV_RX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 101) +#define V4L2_CID_DV_RX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 102) + +#define V4L2_CID_FM_RX_CLASS_BASE (V4L2_CTRL_CLASS_FM_RX | 0x900) +#define V4L2_CID_FM_RX_CLASS (V4L2_CTRL_CLASS_FM_RX | 1) + +#define V4L2_CID_TUNE_DEEMPHASIS (V4L2_CID_FM_RX_CLASS_BASE + 1) +enum v4l2_deemphasis { + V4L2_DEEMPHASIS_DISABLED = V4L2_PREEMPHASIS_DISABLED, + V4L2_DEEMPHASIS_50_uS = V4L2_PREEMPHASIS_50_uS, + V4L2_DEEMPHASIS_75_uS = V4L2_PREEMPHASIS_75_uS, +}; + +#define V4L2_CID_RDS_RECEPTION (V4L2_CID_FM_RX_CLASS_BASE + 2) +#define V4L2_CID_RDS_RX_PTY (V4L2_CID_FM_RX_CLASS_BASE + 3) +#define V4L2_CID_RDS_RX_PS_NAME (V4L2_CID_FM_RX_CLASS_BASE + 4) +#define V4L2_CID_RDS_RX_RADIO_TEXT (V4L2_CID_FM_RX_CLASS_BASE + 5) +#define V4L2_CID_RDS_RX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_RX_CLASS_BASE + 6) +#define V4L2_CID_RDS_RX_TRAFFIC_PROGRAM (V4L2_CID_FM_RX_CLASS_BASE + 7) +#define V4L2_CID_RDS_RX_MUSIC_SPEECH (V4L2_CID_FM_RX_CLASS_BASE + 8) + +#define V4L2_CID_RF_TUNER_CLASS_BASE (V4L2_CTRL_CLASS_RF_TUNER | 0x900) +#define V4L2_CID_RF_TUNER_CLASS (V4L2_CTRL_CLASS_RF_TUNER | 1) + +#define V4L2_CID_RF_TUNER_BANDWIDTH_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 11) +#define V4L2_CID_RF_TUNER_BANDWIDTH (V4L2_CID_RF_TUNER_CLASS_BASE + 12) +#define V4L2_CID_RF_TUNER_RF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 32) +#define V4L2_CID_RF_TUNER_LNA_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 41) +#define V4L2_CID_RF_TUNER_LNA_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 42) +#define V4L2_CID_RF_TUNER_MIXER_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 51) +#define V4L2_CID_RF_TUNER_MIXER_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 52) +#define V4L2_CID_RF_TUNER_IF_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 61) +#define V4L2_CID_RF_TUNER_IF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 62) +#define V4L2_CID_RF_TUNER_PLL_LOCK (V4L2_CID_RF_TUNER_CLASS_BASE + 91) + + +/* Detection-class control IDs defined by V4L2 */ +#define V4L2_CID_DETECT_CLASS_BASE (V4L2_CTRL_CLASS_DETECT | 0x900) +#define V4L2_CID_DETECT_CLASS (V4L2_CTRL_CLASS_DETECT | 1) + +#define V4L2_CID_DETECT_MD_MODE (V4L2_CID_DETECT_CLASS_BASE + 1) +enum v4l2_detect_md_mode { + V4L2_DETECT_MD_MODE_DISABLED = 0, + V4L2_DETECT_MD_MODE_GLOBAL = 1, + V4L2_DETECT_MD_MODE_THRESHOLD_GRID = 2, + V4L2_DETECT_MD_MODE_REGION_GRID = 3, +}; +#define V4L2_CID_DETECT_MD_GLOBAL_THRESHOLD (V4L2_CID_DETECT_CLASS_BASE + 2) +#define V4L2_CID_DETECT_MD_THRESHOLD_GRID (V4L2_CID_DETECT_CLASS_BASE + 3) +#define V4L2_CID_DETECT_MD_REGION_GRID (V4L2_CID_DETECT_CLASS_BASE + 4) + +#endif diff --git a/third_party/openmax/include/OMX_Audio.h b/third_party/openmax/include/OMX_Audio.h deleted file mode 100644 index 0d455766c5..0000000000 --- a/third_party/openmax/include/OMX_Audio.h +++ /dev/null @@ -1,1312 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Audio.h - OpenMax IL version 1.1.2 - * The structures needed by Audio components to exchange - * parameters and configuration data with the componenmilts. - */ - -#ifndef OMX_Audio_h -#define OMX_Audio_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - -/** @defgroup midi MIDI - * @ingroup audio - */ - -/** @defgroup effects Audio effects - * @ingroup audio - */ - -/** @defgroup audio OpenMAX IL Audio Domain - * Structures for OpenMAX IL Audio domain - * @{ - */ - -/** Enumeration used to define the possible audio codings. - * If "OMX_AUDIO_CodingUnused" is selected, the coding selection must - * be done in a vendor specific way. Since this is for an audio - * processing element this enum is relevant. However, for another - * type of component other enums would be in this area. - */ -typedef enum OMX_AUDIO_CODINGTYPE { - OMX_AUDIO_CodingUnused = 0, /**< Placeholder value when coding is N/A */ - OMX_AUDIO_CodingAutoDetect, /**< auto detection of audio format */ - OMX_AUDIO_CodingPCM, /**< Any variant of PCM coding */ - OMX_AUDIO_CodingADPCM, /**< Any variant of ADPCM encoded data */ - OMX_AUDIO_CodingAMR, /**< Any variant of AMR encoded data */ - OMX_AUDIO_CodingGSMFR, /**< Any variant of GSM fullrate (i.e. GSM610) */ - OMX_AUDIO_CodingGSMEFR, /**< Any variant of GSM Enhanced Fullrate encoded data*/ - OMX_AUDIO_CodingGSMHR, /**< Any variant of GSM Halfrate encoded data */ - OMX_AUDIO_CodingPDCFR, /**< Any variant of PDC Fullrate encoded data */ - OMX_AUDIO_CodingPDCEFR, /**< Any variant of PDC Enhanced Fullrate encoded data */ - OMX_AUDIO_CodingPDCHR, /**< Any variant of PDC Halfrate encoded data */ - OMX_AUDIO_CodingTDMAFR, /**< Any variant of TDMA Fullrate encoded data (TIA/EIA-136-420) */ - OMX_AUDIO_CodingTDMAEFR, /**< Any variant of TDMA Enhanced Fullrate encoded data (TIA/EIA-136-410) */ - OMX_AUDIO_CodingQCELP8, /**< Any variant of QCELP 8kbps encoded data */ - OMX_AUDIO_CodingQCELP13, /**< Any variant of QCELP 13kbps encoded data */ - OMX_AUDIO_CodingEVRC, /**< Any variant of EVRC encoded data */ - OMX_AUDIO_CodingSMV, /**< Any variant of SMV encoded data */ - OMX_AUDIO_CodingG711, /**< Any variant of G.711 encoded data */ - OMX_AUDIO_CodingG723, /**< Any variant of G.723 dot 1 encoded data */ - OMX_AUDIO_CodingG726, /**< Any variant of G.726 encoded data */ - OMX_AUDIO_CodingG729, /**< Any variant of G.729 encoded data */ - OMX_AUDIO_CodingAAC, /**< Any variant of AAC encoded data */ - OMX_AUDIO_CodingMP3, /**< Any variant of MP3 encoded data */ - OMX_AUDIO_CodingSBC, /**< Any variant of SBC encoded data */ - OMX_AUDIO_CodingVORBIS, /**< Any variant of VORBIS encoded data */ - OMX_AUDIO_CodingWMA, /**< Any variant of WMA encoded data */ - OMX_AUDIO_CodingRA, /**< Any variant of RA encoded data */ - OMX_AUDIO_CodingMIDI, /**< Any variant of MIDI encoded data */ - OMX_AUDIO_CodingAC3, /**< Any variant of AC3 encoded data */ - OMX_AUDIO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CodingMax = 0x7FFFFFFF -} OMX_AUDIO_CODINGTYPE; - - -/** The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output audio - * path. If additional information is needed to define the parameters of the - * port (such as frequency), additional structures must be sent such as the - * OMX_AUDIO_PARAM_PCMMODETYPE structure to supply the extra parameters for the port. - */ -typedef struct OMX_AUDIO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; /**< MIME type of data for the port */ - OMX_NATIVE_DEVICETYPE pNativeRender; /** < platform specific reference - for an output device, - otherwise this field is 0 */ - OMX_BOOL bFlagErrorConcealment; /**< Turns on error concealment if it is - supported by the OMX component */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this - port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PORTDEFINITIONTYPE; - - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_AUDIO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PARAM_PORTFORMATTYPE; - - -/** PCM mode type */ -typedef enum OMX_AUDIO_PCMMODETYPE { - OMX_AUDIO_PCMModeLinear = 0, /**< Linear PCM encoded data */ - OMX_AUDIO_PCMModeALaw, /**< A law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeMULaw, /**< Mu law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_PCMModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_PCMModeMax = 0x7FFFFFFF -} OMX_AUDIO_PCMMODETYPE; - - -typedef enum OMX_AUDIO_CHANNELTYPE { - OMX_AUDIO_ChannelNone = 0x0, /**< Unused or empty */ - OMX_AUDIO_ChannelLF = 0x1, /**< Left front */ - OMX_AUDIO_ChannelRF = 0x2, /**< Right front */ - OMX_AUDIO_ChannelCF = 0x3, /**< Center front */ - OMX_AUDIO_ChannelLS = 0x4, /**< Left surround */ - OMX_AUDIO_ChannelRS = 0x5, /**< Right surround */ - OMX_AUDIO_ChannelLFE = 0x6, /**< Low frequency effects */ - OMX_AUDIO_ChannelCS = 0x7, /**< Back surround */ - OMX_AUDIO_ChannelLR = 0x8, /**< Left rear. */ - OMX_AUDIO_ChannelRR = 0x9, /**< Right rear. */ - OMX_AUDIO_ChannelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELTYPE; - -#define OMX_AUDIO_MAXCHANNELS 16 /**< maximum number distinct audio channels that a buffer may contain */ -#define OMX_MIN_PCMPAYLOAD_MSEC 5 /**< Minimum audio buffer payload size for uncompressed (PCM) audio */ - -/** PCM format description */ -typedef struct OMX_AUDIO_PARAM_PCMMODETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels (e.g. 2 for stereo) */ - OMX_NUMERICALDATATYPE eNumData; /**< indicates PCM data as signed or unsigned */ - OMX_ENDIANTYPE eEndian; /**< indicates PCM data as little or big endian */ - OMX_BOOL bInterleaved; /**< True for normal interleaved data; false for - non-interleaved data (e.g. block data) */ - OMX_U32 nBitPerSample; /**< Bit per sample */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_AUDIO_PCMMODETYPE ePCMMode; /**< PCM mode enumeration */ - OMX_AUDIO_CHANNELTYPE eChannelMapping[OMX_AUDIO_MAXCHANNELS]; /**< Slot i contains channel defined by eChannelMap[i] */ - -} OMX_AUDIO_PARAM_PCMMODETYPE; - - -/** Audio channel mode. This is used by both AAC and MP3, although the names are more appropriate - * for the MP3. For example, JointStereo for MP3 is CouplingChannels for AAC. - */ -typedef enum OMX_AUDIO_CHANNELMODETYPE { - OMX_AUDIO_ChannelModeStereo = 0, /**< 2 channels, the bitrate allocation between those - two channels changes accordingly to each channel information */ - OMX_AUDIO_ChannelModeJointStereo, /**< mode that takes advantage of what is common between - 2 channels for higher compression gain */ - OMX_AUDIO_ChannelModeDual, /**< 2 mono-channels, each channel is encoded with half - the bitrate of the overall bitrate */ - OMX_AUDIO_ChannelModeMono, /**< Mono channel mode */ - OMX_AUDIO_ChannelModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelModeMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELMODETYPE; - - -typedef enum OMX_AUDIO_MP3STREAMFORMATTYPE { - OMX_AUDIO_MP3StreamFormatMP1Layer3 = 0, /**< MP3 Audio MPEG 1 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2Layer3, /**< MP3 Audio MPEG 2 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2_5Layer3, /**< MP3 Audio MPEG2.5 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MP3StreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MP3StreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MP3STREAMFORMATTYPE; - -/** MP3 params */ -typedef struct OMX_AUDIO_PARAM_MP3TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_MP3STREAMFORMATTYPE eFormat; /**< MP3 stream format */ -} OMX_AUDIO_PARAM_MP3TYPE; - - -typedef enum OMX_AUDIO_AACSTREAMFORMATTYPE { - OMX_AUDIO_AACStreamFormatMP2ADTS = 0, /**< AAC Audio Data Transport Stream 2 format */ - OMX_AUDIO_AACStreamFormatMP4ADTS, /**< AAC Audio Data Transport Stream 4 format */ - OMX_AUDIO_AACStreamFormatMP4LOAS, /**< AAC Low Overhead Audio Stream format */ - OMX_AUDIO_AACStreamFormatMP4LATM, /**< AAC Low overhead Audio Transport Multiplex */ - OMX_AUDIO_AACStreamFormatADIF, /**< AAC Audio Data Interchange Format */ - OMX_AUDIO_AACStreamFormatMP4FF, /**< AAC inside MPEG-4/ISO File Format */ - OMX_AUDIO_AACStreamFormatRAW, /**< AAC Raw Format */ - OMX_AUDIO_AACStreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACStreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACStreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AACSTREAMFORMATTYPE; - - -/** AAC mode type. Note that the term profile is used with the MPEG-2 - * standard and the term object type and profile is used with MPEG-4 */ -typedef enum OMX_AUDIO_AACPROFILETYPE{ - OMX_AUDIO_AACObjectNull = 0, /**< Null, not used */ - OMX_AUDIO_AACObjectMain = 1, /**< AAC Main object */ - OMX_AUDIO_AACObjectLC, /**< AAC Low Complexity object (AAC profile) */ - OMX_AUDIO_AACObjectSSR, /**< AAC Scalable Sample Rate object */ - OMX_AUDIO_AACObjectLTP, /**< AAC Long Term Prediction object */ - OMX_AUDIO_AACObjectHE, /**< AAC High Efficiency (object type SBR, HE-AAC profile) */ - OMX_AUDIO_AACObjectScalable, /**< AAC Scalable object */ - OMX_AUDIO_AACObjectERLC = 17, /**< ER AAC Low Complexity object (Error Resilient AAC-LC) */ - OMX_AUDIO_AACObjectLD = 23, /**< AAC Low Delay object (Error Resilient) */ - OMX_AUDIO_AACObjectHE_PS = 29, /**< AAC High Efficiency with Parametric Stereo coding (HE-AAC v2, object type PS) */ - OMX_AUDIO_AACObjectKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACObjectVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACObjectMax = 0x7FFFFFFF -} OMX_AUDIO_AACPROFILETYPE; - - -/** AAC tool usage (for nAACtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for encoder configuration and optional as decoder info output. - * For MP3, OMX_AUDIO_CHANNELMODETYPE is sufficient. */ -#define OMX_AUDIO_AACToolNone 0x00000000 /**< no AAC tools allowed (encoder config) or active (decoder info output) */ -#define OMX_AUDIO_AACToolMS 0x00000001 /**< MS: Mid/side joint coding tool allowed or active */ -#define OMX_AUDIO_AACToolIS 0x00000002 /**< IS: Intensity stereo tool allowed or active */ -#define OMX_AUDIO_AACToolTNS 0x00000004 /**< TNS: Temporal Noise Shaping tool allowed or active */ -#define OMX_AUDIO_AACToolPNS 0x00000008 /**< PNS: MPEG-4 Perceptual Noise substitution tool allowed or active */ -#define OMX_AUDIO_AACToolLTP 0x00000010 /**< LTP: MPEG-4 Long Term Prediction tool allowed or active */ -#define OMX_AUDIO_AACToolAll 0x7FFFFFFF /**< all AAC tools allowed or active (*/ - -/** MPEG-4 AAC error resilience (ER) tool usage (for nAACERtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for ER encoder configuration and optional as decoder info output */ -#define OMX_AUDIO_AACERNone 0x00000000 /**< no AAC ER tools allowed/used */ -#define OMX_AUDIO_AACERVCB11 0x00000001 /**< VCB11: Virtual Code Books for AAC section data */ -#define OMX_AUDIO_AACERRVLC 0x00000002 /**< RVLC: Reversible Variable Length Coding */ -#define OMX_AUDIO_AACERHCR 0x00000004 /**< HCR: Huffman Codeword Reordering */ -#define OMX_AUDIO_AACERAll 0x7FFFFFFF /**< all AAC ER tools allowed/used */ - - -/** AAC params */ -typedef struct OMX_AUDIO_PARAM_AACPROFILETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_U32 nFrameLength; /**< Frame length (in audio samples per channel) of the codec. - Can be 1024 or 960 (AAC-LC), 2048 (HE-AAC), 480 or 512 (AAC-LD). - Use 0 to let encoder decide */ - OMX_U32 nAACtools; /**< AAC tool usage */ - OMX_U32 nAACERtools; /**< MPEG-4 AAC error resilience tool usage */ - OMX_AUDIO_AACPROFILETYPE eAACProfile; /**< AAC profile enumeration */ - OMX_AUDIO_AACSTREAMFORMATTYPE eAACStreamFormat; /**< AAC stream format enumeration */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ -} OMX_AUDIO_PARAM_AACPROFILETYPE; - - -/** VORBIS params */ -typedef struct OMX_AUDIO_PARAM_VORBISTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the encoded data data. Use 0 for variable - rate or unknown bit rates. Encoding is set to the - bitrate closest to specified value (in bps) */ - OMX_U32 nMinBitRate; /**< Sets minimum bitrate (in bps). */ - OMX_U32 nMaxBitRate; /**< Sets maximum bitrate (in bps). */ - - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_S32 nQuality; /**< Sets encoding quality to n, between -1 (low) and 10 (high). - In the default mode of operation, teh quality level is 3. - Normal quality range is 0 - 10. */ - OMX_BOOL bManaged; /**< Set bitrate management mode. This turns off the - normal VBR encoding, but allows hard or soft bitrate - constraints to be enforced by the encoder. This mode can - be slower, and may also be lower quality. It is - primarily useful for streaming. */ - OMX_BOOL bDownmix; /**< Downmix input from stereo to mono (has no effect on - non-stereo streams). Useful for lower-bitrate encoding. */ -} OMX_AUDIO_PARAM_VORBISTYPE; - - -/** WMA Version */ -typedef enum OMX_AUDIO_WMAFORMATTYPE { - OMX_AUDIO_WMAFormatUnused = 0, /**< format unused or unknown */ - OMX_AUDIO_WMAFormat7, /**< Windows Media Audio format 7 */ - OMX_AUDIO_WMAFormat8, /**< Windows Media Audio format 8 */ - OMX_AUDIO_WMAFormat9, /**< Windows Media Audio format 9 */ - OMX_AUDIO_WMAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_WMAFORMATTYPE; - - -/** WMA Profile */ -typedef enum OMX_AUDIO_WMAPROFILETYPE { - OMX_AUDIO_WMAProfileUnused = 0, /**< profile unused or unknown */ - OMX_AUDIO_WMAProfileL1, /**< Windows Media audio version 9 profile L1 */ - OMX_AUDIO_WMAProfileL2, /**< Windows Media audio version 9 profile L2 */ - OMX_AUDIO_WMAProfileL3, /**< Windows Media audio version 9 profile L3 */ - OMX_AUDIO_WMAProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAProfileMax = 0x7FFFFFFF -} OMX_AUDIO_WMAPROFILETYPE; - - -/** WMA params */ -typedef struct OMX_AUDIO_PARAM_WMATYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_WMAFORMATTYPE eFormat; /**< Version of WMA stream / data */ - OMX_AUDIO_WMAPROFILETYPE eProfile; /**< Profile of WMA stream / data */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data */ - OMX_U16 nBlockAlign; /**< is the block alignment, or block size, in bytes of the audio codec */ - OMX_U16 nEncodeOptions; /**< WMA Type-specific data */ - OMX_U32 nSuperBlockAlign; /**< WMA Type-specific data */ -} OMX_AUDIO_PARAM_WMATYPE; - -/** - * RealAudio format - */ -typedef enum OMX_AUDIO_RAFORMATTYPE { - OMX_AUDIO_RAFormatUnused = 0, /**< Format unused or unknown */ - OMX_AUDIO_RA8, /**< RealAudio 8 codec */ - OMX_AUDIO_RA9, /**< RealAudio 9 codec */ - OMX_AUDIO_RA10_AAC, /**< MPEG-4 AAC codec for bitrates of more than 128kbps */ - OMX_AUDIO_RA10_CODEC, /**< RealAudio codec for bitrates less than 128 kbps */ - OMX_AUDIO_RA10_LOSSLESS, /**< RealAudio Lossless */ - OMX_AUDIO_RA10_MULTICHANNEL, /**< RealAudio Multichannel */ - OMX_AUDIO_RA10_VOICE, /**< RealAudio Voice for bitrates below 15 kbps */ - OMX_AUDIO_RAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_RAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_RAFORMATTYPE; - -/** RA (Real Audio) params */ -typedef struct OMX_AUDIO_PARAM_RATYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSamplingRate; /**< is the sampling rate of the source data */ - OMX_U32 nBitsPerFrame; /**< is the value for bits per frame */ - OMX_U32 nSamplePerFrame; /**< is the value for samples per frame */ - OMX_U32 nCouplingQuantBits; /**< is the number of coupling quantization bits in the stream */ - OMX_U32 nCouplingStartRegion; /**< is the coupling start region in the stream */ - OMX_U32 nNumRegions; /**< is the number of regions value */ - OMX_AUDIO_RAFORMATTYPE eFormat; /**< is the RealAudio audio format */ -} OMX_AUDIO_PARAM_RATYPE; - - -/** SBC Allocation Method Type */ -typedef enum OMX_AUDIO_SBCALLOCMETHODTYPE { - OMX_AUDIO_SBCAllocMethodLoudness, /**< Loudness allocation method */ - OMX_AUDIO_SBCAllocMethodSNR, /**< SNR allocation method */ - OMX_AUDIO_SBCAllocMethodKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_SBCAllocMethodVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_SBCAllocMethodMax = 0x7FFFFFFF -} OMX_AUDIO_SBCALLOCMETHODTYPE; - - -/** SBC params */ -typedef struct OMX_AUDIO_PARAM_SBCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBlocks; /**< Number of blocks */ - OMX_U32 nSubbands; /**< Number of subbands */ - OMX_U32 nBitPool; /**< Bitpool value */ - OMX_BOOL bEnableBitrate; /**< Use bitrate value instead of bitpool */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_SBCALLOCMETHODTYPE eSBCAllocType; /**< SBC Allocation method type */ -} OMX_AUDIO_PARAM_SBCTYPE; - - -/** ADPCM stream format parameters */ -typedef struct OMX_AUDIO_PARAM_ADPCMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitsPerSample; /**< Number of bits in each sample */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ -} OMX_AUDIO_PARAM_ADPCMTYPE; - - -/** G723 rate */ -typedef enum OMX_AUDIO_G723RATE { - OMX_AUDIO_G723ModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_G723ModeLow, /**< 5300 bps */ - OMX_AUDIO_G723ModeHigh, /**< 6300 bps */ - OMX_AUDIO_G723ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G723ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G723ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G723RATE; - - -/** G723 - Sample rate must be 8 KHz */ -typedef struct OMX_AUDIO_PARAM_G723TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G723RATE eBitRate; /**< todo: Should this be moved to a config? */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ - OMX_BOOL bPostFilter; /**< Enable Post Filter */ -} OMX_AUDIO_PARAM_G723TYPE; - - -/** ITU G726 (ADPCM) rate */ -typedef enum OMX_AUDIO_G726MODE { - OMX_AUDIO_G726ModeUnused = 0, /**< G726 Mode unused / unknown */ - OMX_AUDIO_G726Mode16, /**< 16 kbps */ - OMX_AUDIO_G726Mode24, /**< 24 kbps */ - OMX_AUDIO_G726Mode32, /**< 32 kbps, most common rate, also G721 */ - OMX_AUDIO_G726Mode40, /**< 40 kbps */ - OMX_AUDIO_G726ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G726ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G726ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G726MODE; - - -/** G.726 stream format parameters - must be at 8KHz */ -typedef struct OMX_AUDIO_PARAM_G726TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_G726MODE eG726Mode; -} OMX_AUDIO_PARAM_G726TYPE; - - -/** G729 coder type */ -typedef enum OMX_AUDIO_G729TYPE { - OMX_AUDIO_G729 = 0, /**< ITU G.729 encoded data */ - OMX_AUDIO_G729A, /**< ITU G.729 annex A encoded data */ - OMX_AUDIO_G729B, /**< ITU G.729 with annex B encoded data */ - OMX_AUDIO_G729AB, /**< ITU G.729 annexes A and B encoded data */ - OMX_AUDIO_G729KhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G729VendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G729Max = 0x7FFFFFFF -} OMX_AUDIO_G729TYPE; - - -/** G729 stream format parameters - fixed 6KHz sample rate */ -typedef struct OMX_AUDIO_PARAM_G729TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G729TYPE eBitType; -} OMX_AUDIO_PARAM_G729TYPE; - - -/** AMR Frame format */ -typedef enum OMX_AUDIO_AMRFRAMEFORMATTYPE { - OMX_AUDIO_AMRFrameFormatConformance = 0, /**< Frame Format is AMR Conformance - (Standard) Format */ - OMX_AUDIO_AMRFrameFormatIF1, /**< Frame Format is AMR Interface - Format 1 */ - OMX_AUDIO_AMRFrameFormatIF2, /**< Frame Format is AMR Interface - Format 2*/ - OMX_AUDIO_AMRFrameFormatFSF, /**< Frame Format is AMR File Storage - Format */ - OMX_AUDIO_AMRFrameFormatRTPPayload, /**< Frame Format is AMR Real-Time - Transport Protocol Payload Format */ - OMX_AUDIO_AMRFrameFormatITU, /**< Frame Format is ITU Format (added at Motorola request) */ - OMX_AUDIO_AMRFrameFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRFrameFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRFrameFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AMRFRAMEFORMATTYPE; - - -/** AMR band mode */ -typedef enum OMX_AUDIO_AMRBANDMODETYPE { - OMX_AUDIO_AMRBandModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_AMRBandModeNB0, /**< AMRNB Mode 0 = 4750 bps */ - OMX_AUDIO_AMRBandModeNB1, /**< AMRNB Mode 1 = 5150 bps */ - OMX_AUDIO_AMRBandModeNB2, /**< AMRNB Mode 2 = 5900 bps */ - OMX_AUDIO_AMRBandModeNB3, /**< AMRNB Mode 3 = 6700 bps */ - OMX_AUDIO_AMRBandModeNB4, /**< AMRNB Mode 4 = 7400 bps */ - OMX_AUDIO_AMRBandModeNB5, /**< AMRNB Mode 5 = 7950 bps */ - OMX_AUDIO_AMRBandModeNB6, /**< AMRNB Mode 6 = 10200 bps */ - OMX_AUDIO_AMRBandModeNB7, /**< AMRNB Mode 7 = 12200 bps */ - OMX_AUDIO_AMRBandModeWB0, /**< AMRWB Mode 0 = 6600 bps */ - OMX_AUDIO_AMRBandModeWB1, /**< AMRWB Mode 1 = 8850 bps */ - OMX_AUDIO_AMRBandModeWB2, /**< AMRWB Mode 2 = 12650 bps */ - OMX_AUDIO_AMRBandModeWB3, /**< AMRWB Mode 3 = 14250 bps */ - OMX_AUDIO_AMRBandModeWB4, /**< AMRWB Mode 4 = 15850 bps */ - OMX_AUDIO_AMRBandModeWB5, /**< AMRWB Mode 5 = 18250 bps */ - OMX_AUDIO_AMRBandModeWB6, /**< AMRWB Mode 6 = 19850 bps */ - OMX_AUDIO_AMRBandModeWB7, /**< AMRWB Mode 7 = 23050 bps */ - OMX_AUDIO_AMRBandModeWB8, /**< AMRWB Mode 8 = 23850 bps */ - OMX_AUDIO_AMRBandModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRBandModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRBandModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRBANDMODETYPE; - - -/** AMR Discontinuous Transmission mode */ -typedef enum OMX_AUDIO_AMRDTXMODETYPE { - OMX_AUDIO_AMRDTXModeOff = 0, /**< AMR Discontinuous Transmission Mode is disabled */ - OMX_AUDIO_AMRDTXModeOnVAD1, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 1 (VAD1) is enabled */ - OMX_AUDIO_AMRDTXModeOnVAD2, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 2 (VAD2) is enabled */ - OMX_AUDIO_AMRDTXModeOnAuto, /**< The codec will automatically select between - Off, VAD1 or VAD2 modes */ - - OMX_AUDIO_AMRDTXasEFR, /**< DTX as EFR instead of AMR standard (3GPP 26.101, frame type =8,9,10) */ - - OMX_AUDIO_AMRDTXModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRDTXModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRDTXModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRDTXMODETYPE; - - -/** AMR params */ -typedef struct OMX_AUDIO_PARAM_AMRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate read only field */ - OMX_AUDIO_AMRBANDMODETYPE eAMRBandMode; /**< AMR Band Mode enumeration */ - OMX_AUDIO_AMRDTXMODETYPE eAMRDTXMode; /**< AMR DTX Mode enumeration */ - OMX_AUDIO_AMRFRAMEFORMATTYPE eAMRFrameFormat; /**< AMR frame format enumeration */ -} OMX_AUDIO_PARAM_AMRTYPE; - - -/** GSM_FR (ETSI 06.10, 3GPP 46.010) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMFRTYPE; - - -/** GSM-HR (ETSI 06.20, 3GPP 46.020) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMHRTYPE; - - -/** GSM-EFR (ETSI 06.60, 3GPP 46.060) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMEFRTYPE; - - -/** TDMA FR (TIA/EIA-136-420, VSELP 7.95kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAFRTYPE; - - -/** TDMA EFR (TIA/EIA-136-410, ACELP 7.4kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAEFRTYPE; - - -/** PDC FR ( RCR-27, VSELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCFRTYPE; - - -/** PDC EFR ( RCR-27, ACELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCEFRTYPE; - -/** PDC HR ( RCR-27, PSI-CELP 3.45kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCHRTYPE; - - -/** CDMA Rate types */ -typedef enum OMX_AUDIO_CDMARATETYPE { - OMX_AUDIO_CDMARateBlank = 0, /**< CDMA encoded frame is blank */ - OMX_AUDIO_CDMARateFull, /**< CDMA encoded frame in full rate */ - OMX_AUDIO_CDMARateHalf, /**< CDMA encoded frame in half rate */ - OMX_AUDIO_CDMARateQuarter, /**< CDMA encoded frame in quarter rate */ - OMX_AUDIO_CDMARateEighth, /**< CDMA encoded frame in eighth rate (DTX)*/ - OMX_AUDIO_CDMARateErasure, /**< CDMA erasure frame */ - OMX_AUDIO_CDMARateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CDMARateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CDMARateMax = 0x7FFFFFFF -} OMX_AUDIO_CDMARATETYPE; - - -/** QCELP8 (TIA/EIA-96, up to 8kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP8TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP8TYPE; - - -/** QCELP13 ( CDMA, EIA/TIA-733, 13.3kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP13TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP13TYPE; - - -/** EVRC ( CDMA, EIA/TIA-127, RCELP up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_EVRCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< actual Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter */ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter */ -} OMX_AUDIO_PARAM_EVRCTYPE; - - -/** SMV ( up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_SMVTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 ??*/ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 ??*/ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter ??*/ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter ??*/ -} OMX_AUDIO_PARAM_SMVTYPE; - - -/** MIDI Format - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIFORMATTYPE -{ - OMX_AUDIO_MIDIFormatUnknown = 0, /**< MIDI Format unknown or don't care */ - OMX_AUDIO_MIDIFormatSMF0, /**< Standard MIDI File Type 0 */ - OMX_AUDIO_MIDIFormatSMF1, /**< Standard MIDI File Type 1 */ - OMX_AUDIO_MIDIFormatSMF2, /**< Standard MIDI File Type 2 */ - OMX_AUDIO_MIDIFormatSPMIDI, /**< SP-MIDI */ - OMX_AUDIO_MIDIFormatXMF0, /**< eXtensible Music Format type 0 */ - OMX_AUDIO_MIDIFormatXMF1, /**< eXtensible Music Format type 1 */ - OMX_AUDIO_MIDIFormatMobileXMF, /**< Mobile XMF (eXtensible Music Format type 2) */ - OMX_AUDIO_MIDIFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIFORMATTYPE; - - -/** MIDI params - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDITYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nFileSize; /**< size of the MIDI file in bytes, where the entire - MIDI file passed in, otherwise if 0x0, the MIDI data - is merged and streamed (instead of passed as an - entire MIDI file) */ - OMX_BU32 sMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_BOOL bLoadDefaultSound; /**< Whether to load default sound - bank at initialization */ - OMX_AUDIO_MIDIFORMATTYPE eMidiFormat; /**< Version of the MIDI file */ -} OMX_AUDIO_PARAM_MIDITYPE; - - -/** Type of the MIDI sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKTYPE { - OMX_AUDIO_MIDISoundBankUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankDLS1, /**< DLS version 1 */ - OMX_AUDIO_MIDISoundBankDLS2, /**< DLS version 2 */ - OMX_AUDIO_MIDISoundBankMobileDLSBase, /**< Mobile DLS, using the base functionality */ - OMX_AUDIO_MIDISoundBankMobileDLSPlusOptions, /**< Mobile DLS, using the specification-defined optional feature set */ - OMX_AUDIO_MIDISoundBankKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKTYPE; - - -/** Bank Layout describes how bank MSB & LSB are used in the DLS instrument definitions sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE { - OMX_AUDIO_MIDISoundBankLayoutUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankLayoutGM, /**< GS layout (based on bank MSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutGM2, /**< General MIDI 2 layout (using MSB 0x78/0x79, LSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutUser, /**< Does not conform to any bank numbering standards */ - OMX_AUDIO_MIDISoundBankLayoutKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankLayoutVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankLayoutMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE; - - -/** MIDI params to load/unload user soundbank - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nDLSIndex; /**< DLS file index to be loaded */ - OMX_U32 nDLSSize; /**< Size in bytes */ - OMX_PTR pDLSData; /**< Pointer to DLS file data */ - OMX_AUDIO_MIDISOUNDBANKTYPE eMidiSoundBank; /**< Midi sound bank type enumeration */ - OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE eMidiSoundBankLayout; /**< Midi sound bank layout enumeration */ -} OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE; - - -/** Structure for Live MIDI events and MIP messages. - * (MIP = Maximum Instantaneous Polyphony; part of the SP-MIDI standard.) - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nMidiEventSize; /**< Size of immediate MIDI events or MIP message in bytes */ - OMX_U8 nMidiEvents[1]; /**< MIDI event array to be rendered immediately, or an - array for the MIP message buffer, where the size is - indicated by nMidiEventSize */ -} OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE; - - -/** MIDI sound bank/ program pair in a given channel - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannel; /**< Valid channel values range from 1 to 16 */ - OMX_U16 nIDProgram; /**< Valid program ID range is 1 to 128 */ - OMX_U16 nIDSoundBank; /**< Sound bank ID */ - OMX_U32 nUserSoundBankIndex;/**< User soundbank index, easier to access soundbanks - by index if multiple banks are present */ -} OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE; - - -/** MIDI control - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDICONTROLTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BS32 sPitchTransposition; /**< Pitch transposition in semitones, stored as Q22.10 - format based on JAVA MMAPI (JSR-135) requirement */ - OMX_BU32 sPlayBackRate; /**< Relative playback rate, stored as Q14.17 fixed-point - number based on JSR-135 requirement */ - OMX_BU32 sTempo ; /**< Tempo in beats per minute (BPM), stored as Q22.10 - fixed-point number based on JSR-135 requirement */ - OMX_U32 nMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_U32 nNumRepeat; /**< Number of times to repeat playback */ - OMX_U32 nStopTime; /**< Time in milliseconds to indicate when playback - will stop automatically. Set to zero if not used */ - OMX_U16 nChannelMuteMask; /**< 16 bit mask for channel mute status */ - OMX_U16 nChannelSoloMask; /**< 16 bit mask for channel solo status */ - OMX_U32 nTrack0031MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 32-63 */ - OMX_U32 nTrack0031SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 32-63 */ - -} OMX_AUDIO_CONFIG_MIDICONTROLTYPE; - - -/** MIDI Playback States - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIPLAYBACKSTATETYPE { - OMX_AUDIO_MIDIPlayBackStateUnknown = 0, /**< Unknown state or state does not map to - other defined states */ - OMX_AUDIO_MIDIPlayBackStateClosedEngaged, /**< No MIDI resource is currently open. - The MIDI engine is currently processing - MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateParsing, /**< A MIDI resource is open and is being - primed. The MIDI engine is currently - processing MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateOpenEngaged, /**< A MIDI resource is open and primed but - not playing. The MIDI engine is currently - processing MIDI events. The transition to - this state is only possible from the - OMX_AUDIO_MIDIPlayBackStatePlaying state, - when the 'playback head' reaches the end - of media data or the playback stops due - to stop time set.*/ - OMX_AUDIO_MIDIPlayBackStatePlaying, /**< A MIDI resource is open and currently - playing. The MIDI engine is currently - processing MIDI events.*/ - OMX_AUDIO_MIDIPlayBackStatePlayingPartially, /**< Best-effort playback due to SP-MIDI/DLS - resource constraints */ - OMX_AUDIO_MIDIPlayBackStatePlayingSilently, /**< Due to system resource constraints and - SP-MIDI content constraints, there is - no audible MIDI content during playback - currently. The situation may change if - resources are freed later.*/ - OMX_AUDIO_MIDIPlayBackStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIPlayBackStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIPlayBackStateMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIPLAYBACKSTATETYPE; - - -/** MIDI status - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISTATUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nNumTracks; /**< Number of MIDI tracks in the file, read only field. - NOTE: May not return a meaningful value until the entire - file is parsed and buffered. */ - OMX_U32 nDuration; /**< The length of the currently open MIDI resource - in milliseconds. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nPosition; /**< Current Position of the MIDI resource being played - in milliseconds */ - OMX_BOOL bVibra; /**< Does Vibra track exist? NOTE: May not return a meaningful - value until the entire file is parsed and buffered. */ - OMX_U32 nNumMetaEvents; /**< Total number of MIDI Meta Events in the currently - open MIDI resource. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nNumActiveVoices; /**< Number of active voices in the currently playing - MIDI resource. NOTE: May not return a meaningful value until - the entire file is parsed and buffered. */ - OMX_AUDIO_MIDIPLAYBACKSTATETYPE eMIDIPlayBackState; /**< MIDI playback state enumeration, read only field */ -} OMX_AUDIO_CONFIG_MIDISTATUSTYPE; - - -/** MIDI Meta Event structure one per Meta Event. - * MIDI Meta Events are like audio metadata, except that they are interspersed - * with the MIDI content throughout the file and are not localized in the header. - * As such, it is necessary to retrieve information about these Meta Events from - * the engine, as it encounters these Meta Events within the MIDI content. - * For example, SMF files can have up to 14 types of MIDI Meta Events (copyright, - * author, default tempo, etc.) scattered throughout the file. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U8 nMetaEventType; /**< Meta Event Type, 7bits (i.e. 0 - 127) */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U32 nTrack; /**< track number for the meta event */ - OMX_U32 nPosition; /**< Position of the meta-event in milliseconds */ -} OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE; - - -/** MIDI Meta Event Data structure - one per Meta Event. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U8 nData[1]; /**< array of one or more bytes of meta data - as indicated by the nMetaEventSize field */ -} OMX_AUDIO_CONFIG__MIDIMETAEVENTDATATYPE; - - -/** Audio Volume adjustment for a port */ -typedef struct OMX_AUDIO_CONFIG_VOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) - or logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. The values - for volume are in mB (millibels = 1/100 dB) relative - to a gain of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ -} OMX_AUDIO_CONFIG_VOLUMETYPE; - - -/** Audio Volume adjustment for a channel */ -typedef struct OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply volume settings - to all channels */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) or - logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. - The values for volume are in mB - (millibels = 1/100 dB) relative to a gain - of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE; - - -/** Audio balance setting */ -typedef struct OMX_AUDIO_CONFIG_BALANCETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's balance. Select the - output port to adjust the master - balance. */ - OMX_S32 nBalance; /**< balance setting for this port - (-100 to 100, where -100 indicates - all left, and no right */ -} OMX_AUDIO_CONFIG_BALANCETYPE; - - -/** Audio Port mute */ -typedef struct OMX_AUDIO_CONFIG_MUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's mute. Select the - output port to adjust the master - mute. */ - OMX_BOOL bMute; /**< Mute setting for this port */ -} OMX_AUDIO_CONFIG_MUTETYPE; - - -/** Audio Channel mute */ -typedef struct OMX_AUDIO_CONFIG_CHANNELMUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply mute settings - to all channels */ - OMX_BOOL bMute; /**< Mute setting for this channel */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELMUTETYPE; - - - -/** Enable / Disable for loudness control, which boosts bass and to a - * smaller extent high end frequencies to compensate for hearing - * ability at the extreme ends of the audio spectrum - */ -typedef struct OMX_AUDIO_CONFIG_LOUDNESSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bLoudness; /**< Enable/disable for loudness */ -} OMX_AUDIO_CONFIG_LOUDNESSTYPE; - - -/** Enable / Disable for bass, which controls low frequencies - */ -typedef struct OMX_AUDIO_CONFIG_BASSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for bass control */ - OMX_S32 nBass; /**< bass setting for the port, as a - continuous value from -100 to 100 - (0 means no change in bass level)*/ -} OMX_AUDIO_CONFIG_BASSTYPE; - - -/** Enable / Disable for treble, which controls high frequencies tones - */ -typedef struct OMX_AUDIO_CONFIG_TREBLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for treble control */ - OMX_S32 nTreble; /**< treble setting for the port, as a - continuous value from -100 to 100 - (0 means no change in treble level) */ -} OMX_AUDIO_CONFIG_TREBLETYPE; - - -/** An equalizer is typically used for two reasons: to compensate for an - * sub-optimal frequency response of a system to make it sound more natural - * or to create intentionally some unnatural coloring to the sound to create - * an effect. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_EQUALIZERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for equalizer */ - OMX_BU32 sBandIndex; /**< Band number to be set. Upper Limit is - N-1, where N is the number of bands, lower limit is 0 */ - OMX_BU32 sCenterFreq; /**< Center frequecies in Hz. This is a - read only element and is used to determine - the lower, center and upper frequency of - this band. */ - OMX_BS32 sBandLevel; /**< band level in millibels */ -} OMX_AUDIO_CONFIG_EQUALIZERTYPE; - - -/** Stereo widening mode type - * @ingroup effects - */ -typedef enum OMX_AUDIO_STEREOWIDENINGTYPE { - OMX_AUDIO_StereoWideningHeadphones, /**< Stereo widening for loudspeakers */ - OMX_AUDIO_StereoWideningLoudspeakers, /**< Stereo widening for closely spaced loudspeakers */ - OMX_AUDIO_StereoWideningKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_StereoWideningVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_StereoWideningMax = 0x7FFFFFFF -} OMX_AUDIO_STEREOWIDENINGTYPE; - - -/** Control for stereo widening, which is a special 2-channel - * case of the audio virtualizer effect. For example, for 5.1-channel - * output, it translates to virtual surround sound. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for stereo widening control */ - OMX_AUDIO_STEREOWIDENINGTYPE eWideningType; /**< Stereo widening algorithm type */ - OMX_U32 nStereoWidening; /**< stereo widening setting for the port, - as a continuous value from 0 to 100 */ -} OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE; - - -/** The chorus effect (or ``choralizer'') is any signal processor which makes - * one sound source (such as a voice) sound like many such sources singing - * (or playing) in unison. Since performance in unison is never exact, chorus - * effects simulate this by making independently modified copies of the input - * signal. Modifications may include (1) delay, (2) frequency shift, and - * (3) amplitude modulation. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_CHORUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for chorus */ - OMX_BU32 sDelay; /**< average delay in milliseconds */ - OMX_BU32 sModulationRate; /**< rate of modulation in millihertz */ - OMX_U32 nModulationDepth; /**< depth of modulation as a percentage of - delay (i.e. 0 to 100) */ - OMX_BU32 nFeedback; /**< Feedback from chorus output to input in percentage */ -} OMX_AUDIO_CONFIG_CHORUSTYPE; - - -/** Reverberation is part of the reflected sound that follows the early - * reflections. In a typical room, this consists of a dense succession of - * echoes whose energy decays exponentially. The reverberation effect structure - * as defined here includes both (early) reflections as well as (late) reverberations. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_REVERBERATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for reverberation control */ - OMX_BS32 sRoomLevel; /**< Intensity level for the whole room effect - (i.e. both early reflections and late - reverberation) in millibels */ - OMX_BS32 sRoomHighFreqLevel; /**< Attenuation at high frequencies - relative to the intensity at low - frequencies in millibels */ - OMX_BS32 sReflectionsLevel; /**< Intensity level of early reflections - (relative to room value), in millibels */ - OMX_BU32 sReflectionsDelay; /**< Delay time of the first reflection relative - to the direct path, in milliseconds */ - OMX_BS32 sReverbLevel; /**< Intensity level of late reverberation - relative to room level, in millibels */ - OMX_BU32 sReverbDelay; /**< Time delay from the first early reflection - to the beginning of the late reverberation - section, in milliseconds */ - OMX_BU32 sDecayTime; /**< Late reverberation decay time at low - frequencies, in milliseconds */ - OMX_BU32 nDecayHighFreqRatio; /**< Ratio of high frequency decay time relative - to low frequency decay time in percent */ - OMX_U32 nDensity; /**< Modal density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_U32 nDiffusion; /**< Echo density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_BU32 sReferenceHighFreq; /**< Reference high frequency in Hertz. This is - the frequency used as the reference for all - the high-frequency settings above */ - -} OMX_AUDIO_CONFIG_REVERBERATIONTYPE; - - -/** Possible settings for the Echo Cancelation structure to use - * @ingroup effects - */ -typedef enum OMX_AUDIO_ECHOCANTYPE { - OMX_AUDIO_EchoCanOff = 0, /**< Echo Cancellation is disabled */ - OMX_AUDIO_EchoCanNormal, /**< Echo Cancellation normal operation - - echo from plastics and face */ - OMX_AUDIO_EchoCanHFree, /**< Echo Cancellation optimized for - Hands Free operation */ - OMX_AUDIO_EchoCanCarKit, /**< Echo Cancellation optimized for - Car Kit (longer echo) */ - OMX_AUDIO_EchoCanKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_EchoCanVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_EchoCanMax = 0x7FFFFFFF -} OMX_AUDIO_ECHOCANTYPE; - - -/** Enable / Disable for echo cancelation, which removes undesired echo's - * from the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_AUDIO_ECHOCANTYPE eEchoCancelation; /**< Echo cancelation settings */ -} OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE; - - -/** Enable / Disable for noise reduction, which undesired noise from - * the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bNoiseReduction; /**< Enable/disable for noise reduction */ -} OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_Component.h b/third_party/openmax/include/OMX_Component.h deleted file mode 100644 index d5956405e2..0000000000 --- a/third_party/openmax/include/OMX_Component.h +++ /dev/null @@ -1,579 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Component.h - OpenMax IL version 1.1.2 - * The OMX_Component header file contains the definitions used to define - * the public interface of a component. This header file is intended to - * be used by both the application and the component. - */ - -#ifndef OMX_Component_h -#define OMX_Component_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include -#include -#include -#include - -/** @ingroup comp */ -typedef enum OMX_PORTDOMAINTYPE { - OMX_PortDomainAudio, - OMX_PortDomainVideo, - OMX_PortDomainImage, - OMX_PortDomainOther, - OMX_PortDomainKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_PortDomainVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_PortDomainMax = 0x7ffffff -} OMX_PORTDOMAINTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /**< Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - OMX_DIRTYPE eDir; /**< Direction (input or output) of this port */ - OMX_U32 nBufferCountActual; /**< The actual number of buffers allocated on this port */ - OMX_U32 nBufferCountMin; /**< The minimum number of buffers this port requires */ - OMX_U32 nBufferSize; /**< Size, in bytes, for buffers to be used for this channel */ - OMX_BOOL bEnabled; /**< Ports default to enabled and are enabled/disabled by - OMX_CommandPortEnable/OMX_CommandPortDisable. - When disabled a port is unpopulated. A disabled port - is not populated with buffers on a transition to IDLE. */ - OMX_BOOL bPopulated; /**< Port is populated with all of its buffers as indicated by - nBufferCountActual. A disabled port is always unpopulated. - An enabled port is populated on a transition to OMX_StateIdle - and unpopulated on a transition to loaded. */ - OMX_PORTDOMAINTYPE eDomain; /**< Domain of the port. Determines the contents of metadata below. */ - union { - OMX_AUDIO_PORTDEFINITIONTYPE audio; - OMX_VIDEO_PORTDEFINITIONTYPE video; - OMX_IMAGE_PORTDEFINITIONTYPE image; - OMX_OTHER_PORTDEFINITIONTYPE other; - } format; - OMX_BOOL bBuffersContiguous; - OMX_U32 nBufferAlignment; -} OMX_PARAM_PORTDEFINITIONTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_U32TYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nU32; /**< U32 value */ -} OMX_PARAM_U32TYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONPOLICYTYPE { - OMX_SuspensionDisabled, /**< No suspension; v1.0 behavior */ - OMX_SuspensionEnabled, /**< Suspension allowed */ - OMX_SuspensionPolicyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionPolicyStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspensionPolicyMax = 0x7fffffff -} OMX_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONPOLICYTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONPOLICYTYPE ePolicy; -} OMX_PARAM_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONTYPE { - OMX_NotSuspended, /**< component is not suspended */ - OMX_Suspended, /**< component is suspended */ - OMX_SuspensionKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspendMax = 0x7FFFFFFF -} OMX_SUSPENSIONTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONTYPE eType; -} OMX_PARAM_SUSPENSIONTYPE ; - -typedef struct OMX_CONFIG_BOOLEANTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bEnabled; -} OMX_CONFIG_BOOLEANTYPE; - -/* Parameter specifying the content uri to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTURITYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes, including - actual URI name */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 contentURI[1]; /**< The URI name */ -} OMX_PARAM_CONTENTURITYPE; - -/* Parameter specifying the pipe to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTPIPETYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_HANDLETYPE hPipe; /**< The pipe handle*/ -} OMX_PARAM_CONTENTPIPETYPE; - -/** @ingroup rpm */ -typedef struct OMX_RESOURCECONCEALMENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bResourceConcealmentForbidden; /**< disallow the use of resource concealment - methods (like degrading algorithm quality to - lower resource consumption or functional bypass) - on a component as a resolution to resource conflicts. */ -} OMX_RESOURCECONCEALMENTTYPE; - - -/** @ingroup metadata */ -typedef enum OMX_METADATACHARSETTYPE { - OMX_MetadataCharsetUnknown = 0, - OMX_MetadataCharsetASCII, - OMX_MetadataCharsetBinary, - OMX_MetadataCharsetCodePage1252, - OMX_MetadataCharsetUTF8, - OMX_MetadataCharsetJavaConformantUTF8, - OMX_MetadataCharsetUTF7, - OMX_MetadataCharsetImapUTF7, - OMX_MetadataCharsetUTF16LE, - OMX_MetadataCharsetUTF16BE, - OMX_MetadataCharsetGB12345, - OMX_MetadataCharsetHZGB2312, - OMX_MetadataCharsetGB2312, - OMX_MetadataCharsetGB18030, - OMX_MetadataCharsetGBK, - OMX_MetadataCharsetBig5, - OMX_MetadataCharsetISO88591, - OMX_MetadataCharsetISO88592, - OMX_MetadataCharsetISO88593, - OMX_MetadataCharsetISO88594, - OMX_MetadataCharsetISO88595, - OMX_MetadataCharsetISO88596, - OMX_MetadataCharsetISO88597, - OMX_MetadataCharsetISO88598, - OMX_MetadataCharsetISO88599, - OMX_MetadataCharsetISO885910, - OMX_MetadataCharsetISO885913, - OMX_MetadataCharsetISO885914, - OMX_MetadataCharsetISO885915, - OMX_MetadataCharsetShiftJIS, - OMX_MetadataCharsetISO2022JP, - OMX_MetadataCharsetISO2022JP1, - OMX_MetadataCharsetISOEUCJP, - OMX_MetadataCharsetSMS7Bit, - OMX_MetadataCharsetKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataCharsetVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataCharsetTypeMax= 0x7FFFFFFF -} OMX_METADATACHARSETTYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASCOPETYPE -{ - OMX_MetadataScopeAllLevels, - OMX_MetadataScopeTopLevel, - OMX_MetadataScopePortLevel, - OMX_MetadataScopeNodeLevel, - OMX_MetadataScopeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataScopeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataScopeTypeMax = 0x7fffffff -} OMX_METADATASCOPETYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASEARCHMODETYPE -{ - OMX_MetadataSearchValueSizeByIndex, - OMX_MetadataSearchItemByIndex, - OMX_MetadataSearchNextItemByKey, - OMX_MetadataSearchKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataSearchVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataSearchTypeMax = 0x7fffffff -} OMX_METADATASEARCHMODETYPE; -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMCOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemCount; -} OMX_CONFIG_METADATAITEMCOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemIndex; - OMX_METADATASEARCHMODETYPE eSearchMode; - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U8 nKeySizeUsed; - OMX_U8 nKey[128]; - OMX_METADATACHARSETTYPE eValueCharset; - OMX_STRING sLanguageCountry; - OMX_U32 nValueMaxSize; - OMX_U32 nValueSizeUsed; - OMX_U8 nValue[1]; -} OMX_CONFIG_METADATAITEMTYPE; - -/* @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODECOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNumNodes; -} OMX_CONFIG_CONTAINERNODECOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODEIDTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNodeIndex; - OMX_U32 nNodeID; - OMX_STRING cNodeName; - OMX_BOOL bIsLeafType; -} OMX_CONFIG_CONTAINERNODEIDTYPE; - -/** @ingroup metadata */ -typedef struct OMX_PARAM_METADATAFILTERTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; /* if true then this structure refers to all keys and - * the three key fields below are ignored */ - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U32 nKeySizeUsed; - OMX_U8 nKey [128]; - OMX_U32 nLanguageCountrySizeUsed; - OMX_U8 nLanguageCountry[128]; - OMX_BOOL bEnabled; /* if true then key is part of filter (e.g. - * retained for query later). If false then - * key is not part of filter */ -} OMX_PARAM_METADATAFILTERTYPE; - -/** The OMX_HANDLETYPE structure defines the component handle. The component - * handle is used to access all of the component's public methods and also - * contains pointers to the component's private data area. The component - * handle is initialized by the OMX core (with help from the component) - * during the process of loading the component. After the component is - * successfully loaded, the application can safely access any of the - * component's public functions (although some may return an error because - * the state is inappropriate for the access). - * - * @ingroup comp - */ -typedef struct OMX_COMPONENTTYPE -{ - /** The size of this structure, in bytes. It is the responsibility - of the allocator of this structure to fill in this value. Since - this structure is allocated by the GetHandle function, this - function will fill in this value. */ - OMX_U32 nSize; - - /** nVersion is the version of the OMX specification that the structure - is built against. It is the responsibility of the creator of this - structure to initialize this value and every user of this structure - should verify that it knows how to use the exact version of - this structure found herein. */ - OMX_VERSIONTYPE nVersion; - - /** pComponentPrivate is a pointer to the component private data area. - This member is allocated and initialized by the component when the - component is first loaded. The application should not access this - data area. */ - OMX_PTR pComponentPrivate; - - /** pApplicationPrivate is a pointer that is a parameter to the - OMX_GetHandle method, and contains an application private value - provided by the IL client. This application private data is - returned to the IL Client by OMX in all callbacks */ - OMX_PTR pApplicationPrivate; - - /** refer to OMX_GetComponentVersion in OMX_core.h or the OMX IL - specification for details on the GetComponentVersion method. - */ - OMX_ERRORTYPE (*GetComponentVersion)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STRING pComponentName, - OMX_OUT OMX_VERSIONTYPE* pComponentVersion, - OMX_OUT OMX_VERSIONTYPE* pSpecVersion, - OMX_OUT OMX_UUIDTYPE* pComponentUUID); - - /** refer to OMX_SendCommand in OMX_core.h or the OMX IL - specification for details on the SendCommand method. - */ - OMX_ERRORTYPE (*SendCommand)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_COMMANDTYPE Cmd, - OMX_IN OMX_U32 nParam1, - OMX_IN OMX_PTR pCmdData); - - /** refer to OMX_GetParameter in OMX_core.h or the OMX IL - specification for details on the GetParameter method. - */ - OMX_ERRORTYPE (*GetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nParamIndex, - OMX_INOUT OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_SetParameter in OMX_core.h or the OMX IL - specification for details on the SetParameter method. - */ - OMX_ERRORTYPE (*SetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_GetConfig in OMX_core.h or the OMX IL - specification for details on the GetConfig method. - */ - OMX_ERRORTYPE (*GetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_INOUT OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_SetConfig in OMX_core.h or the OMX IL - specification for details on the SetConfig method. - */ - OMX_ERRORTYPE (*SetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_GetExtensionIndex in OMX_core.h or the OMX IL - specification for details on the GetExtensionIndex method. - */ - OMX_ERRORTYPE (*GetExtensionIndex)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_STRING cParameterName, - OMX_OUT OMX_INDEXTYPE* pIndexType); - - - /** refer to OMX_GetState in OMX_core.h or the OMX IL - specification for details on the GetState method. - */ - OMX_ERRORTYPE (*GetState)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STATETYPE* pState); - - - /** The ComponentTunnelRequest method will interact with another OMX - component to determine if tunneling is possible and to setup the - tunneling. The return codes for this method can be used to - determine if tunneling is not possible, or if tunneling is not - supported. - - Base profile components (i.e. non-interop) do not support this - method and should return OMX_ErrorNotImplemented - - The interop profile component MUST support tunneling to another - interop profile component with a compatible port parameters. - A component may also support proprietary communication. - - If proprietary communication is supported the negotiation of - proprietary communication is done outside of OMX in a vendor - specific way. It is only required that the proper result be - returned and the details of how the setup is done is left - to the component implementation. - - When this method is invoked when nPort in an output port, the - component will: - 1. Populate the pTunnelSetup structure with the output port's - requirements and constraints for the tunnel. - - When this method is invoked when nPort in an input port, the - component will: - 1. Query the necessary parameters from the output port to - determine if the ports are compatible for tunneling - 2. If the ports are compatible, the component should store - the tunnel step provided by the output port - 3. Determine which port (either input or output) is the buffer - supplier, and call OMX_SetParameter on the output port to - indicate this selection. - - The component will return from this call within 5 msec. - - @param [in] hComp - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle method. - @param [in] nPort - nPort is used to select the port on the component to be used - for tunneling. - @param [in] hTunneledComp - Handle of the component to tunnel with. This is the component - handle returned by the call to the OMX_GetHandle method. When - this parameter is 0x0 the component should setup the port for - communication with the application / IL Client. - @param [in] nPortOutput - nPortOutput is used indicate the port the component should - tunnel with. - @param [in] pTunnelSetup - Pointer to the tunnel setup structure. When nPort is an output port - the component should populate the fields of this structure. When - When nPort is an input port the component should review the setup - provided by the component with the output port. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup tun - */ - - OMX_ERRORTYPE (*ComponentTunnelRequest)( - OMX_IN OMX_HANDLETYPE hComp, - OMX_IN OMX_U32 nPort, - OMX_IN OMX_HANDLETYPE hTunneledComp, - OMX_IN OMX_U32 nTunneledPort, - OMX_INOUT OMX_TUNNELSETUPTYPE* pTunnelSetup); - - /** refer to OMX_UseBuffer in OMX_core.h or the OMX IL - specification for details on the UseBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*UseBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes, - OMX_IN OMX_U8* pBuffer); - - /** refer to OMX_AllocateBuffer in OMX_core.h or the OMX IL - specification for details on the AllocateBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*AllocateBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBuffer, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes); - - /** refer to OMX_FreeBuffer in OMX_core.h or the OMX IL - specification for details on the FreeBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FreeBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_EmptyThisBuffer in OMX_core.h or the OMX IL - specification for details on the EmptyThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_FillThisBuffer in OMX_core.h or the OMX IL - specification for details on the FillThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FillThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The SetCallbacks method is used by the core to specify the callback - structure from the application to the component. This is a blocking - call. The component will return from this call within 5 msec. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] pCallbacks - pointer to an OMX_CALLBACKTYPE structure used to provide the - callback information to the component - @param [in] pAppData - pointer to an application defined value. It is anticipated that - the application will pass a pointer to a data structure or a "this - pointer" in this area to allow the callback (in the application) - to determine the context of the call - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*SetCallbacks)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_CALLBACKTYPE* pCallbacks, - OMX_IN OMX_PTR pAppData); - - /** ComponentDeInit method is used to deinitialize the component - providing a means to free any resources allocated at component - initialization. NOTE: After this call the component handle is - not valid for further use. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*ComponentDeInit)( - OMX_IN OMX_HANDLETYPE hComponent); - - /** @ingroup buf */ - OMX_ERRORTYPE (*UseEGLImage)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN void* eglImage); - - OMX_ERRORTYPE (*ComponentRoleEnum)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_U8 *cRole, - OMX_IN OMX_U32 nIndex); - -} OMX_COMPONENTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_ContentPipe.h b/third_party/openmax/include/OMX_ContentPipe.h deleted file mode 100644 index 5f6310c28a..0000000000 --- a/third_party/openmax/include/OMX_ContentPipe.h +++ /dev/null @@ -1,195 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_ContentPipe.h - OpenMax IL version 1.1.2 - * The OMX_ContentPipe header file contains the definitions used to define - * the public interface for content piples. This header file is intended to - * be used by the component. - */ - -#ifndef OMX_CONTENTPIPE_H -#define OMX_CONTENTPIPE_H - -#ifndef KD_EACCES -/* OpenKODE error codes. CPResult values may be zero (indicating success - or one of the following values) */ -#define KD_EACCES (1) -#define KD_EADDRINUSE (2) -#define KD_EAGAIN (5) -#define KD_EBADF (7) -#define KD_EBUSY (8) -#define KD_ECONNREFUSED (9) -#define KD_ECONNRESET (10) -#define KD_EDEADLK (11) -#define KD_EDESTADDRREQ (12) -#define KD_ERANGE (35) -#define KD_EEXIST (13) -#define KD_EFBIG (14) -#define KD_EHOSTUNREACH (15) -#define KD_EINVAL (17) -#define KD_EIO (18) -#define KD_EISCONN (20) -#define KD_EISDIR (21) -#define KD_EMFILE (22) -#define KD_ENAMETOOLONG (23) -#define KD_ENOENT (24) -#define KD_ENOMEM (25) -#define KD_ENOSPC (26) -#define KD_ENOSYS (27) -#define KD_ENOTCONN (28) -#define KD_EPERM (33) -#define KD_ETIMEDOUT (36) -#define KD_EILSEQ (19) -#endif - -/** Map types from OMX standard types only here so interface is as generic as possible. */ -typedef OMX_U32 CPresult; -typedef char * CPstring; -typedef void * CPhandle; -typedef OMX_U32 CPuint; -typedef OMX_S32 CPint; -typedef char CPbyte; -typedef OMX_BOOL CPbool; - -/** enumeration of origin types used in the CP_PIPETYPE's Seek function - * @ingroup cp - */ -typedef enum CP_ORIGINTYPE { - CP_OriginBegin, - CP_OriginCur, - CP_OriginEnd, - CP_OriginKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_OriginVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_OriginMax = 0X7FFFFFFF -} CP_ORIGINTYPE; - -/** enumeration of contact access types used in the CP_PIPETYPE's Open function - * @ingroup cp - */ -typedef enum CP_ACCESSTYPE { - CP_AccessRead, - CP_AccessWrite, - CP_AccessReadWrite , - CP_AccessKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_AccessVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_AccessMax = 0X7FFFFFFF -} CP_ACCESSTYPE; - -/** enumeration of results returned by the CP_PIPETYPE's CheckAvailableBytes function - * @ingroup cp - */ -typedef enum CP_CHECKBYTESRESULTTYPE -{ - CP_CheckBytesOk, /**< There are at least the request number - of bytes available */ - CP_CheckBytesNotReady, /**< The pipe is still retrieving bytes - and presently lacks sufficient bytes. - Client will be called when they are - sufficient bytes are available. */ - CP_CheckBytesInsufficientBytes , /**< The pipe has retrieved all bytes - but those available are less than those - requested */ - CP_CheckBytesAtEndOfStream, /**< The pipe has reached the end of stream - and no more bytes are available. */ - CP_CheckBytesOutOfBuffers, /**< All read/write buffers are currently in use. */ - CP_CheckBytesKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_CheckBytesVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_CheckBytesMax = 0X7FFFFFFF -} CP_CHECKBYTESRESULTTYPE; - -/** enumeration of content pipe events sent to the client callback. - * @ingroup cp - */ -typedef enum CP_EVENTTYPE{ - CP_BytesAvailable, /** bytes requested in a CheckAvailableBytes call are now available*/ - CP_Overflow, /** enumeration of content pipe events sent to the client callback*/ - CP_PipeDisconnected , /** enumeration of content pipe events sent to the client callback*/ - CP_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_EventMax = 0X7FFFFFFF -} CP_EVENTTYPE; - -/** content pipe definition - * @ingroup cp - */ -typedef struct CP_PIPETYPE -{ - /** Open a content stream for reading or writing. */ - CPresult (*Open)( CPhandle* hContent, CPstring szURI, CP_ACCESSTYPE eAccess ); - - /** Close a content stream. */ - CPresult (*Close)( CPhandle hContent ); - - /** Create a content source and open it for writing. */ - CPresult (*Create)( CPhandle *hContent, CPstring szURI ); - - /** Check the that specified number of bytes are available for reading or writing (depending on access type).*/ - CPresult (*CheckAvailableBytes)( CPhandle hContent, CPuint nBytesRequested, CP_CHECKBYTESRESULTTYPE *eResult ); - - /** Seek to certain position in the content relative to the specified origin. */ - CPresult (*SetPosition)( CPhandle hContent, CPint nOffset, CP_ORIGINTYPE eOrigin); - - /** Retrieve the current position relative to the start of the content. */ - CPresult (*GetPosition)( CPhandle hContent, CPuint *pPosition); - - /** Retrieve data of the specified size from the content stream (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency reads. */ - CPresult (*Read)( CPhandle hContent, CPbyte *pData, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe that contains the requested number of bytes. - Buffer contains the next block of bytes, as specified by nSize, of the content. nSize also - returns the size of the block actually read. Content pointer advances the by the returned size. - Note: pipe provides pointer. This function is appropriate for large reads. The client must call - ReleaseReadBuffer when done with buffer. - - In some cases the requested block may not reside in contiguous memory within the - pipe implementation. For instance if the pipe leverages a circular buffer then the requested - block may straddle the boundary of the circular buffer. By default a pipe implementation - performs a copy in this case to provide the block to the pipe client in one contiguous buffer. - If, however, the client sets bForbidCopy, then the pipe returns only those bytes preceding the memory - boundary. Here the client may retrieve the data in segments over successive calls. */ - CPresult (*ReadBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint *nSize, CPbool bForbidCopy); - - /** Release a buffer obtained by ReadBuffer back to the pipe. */ - CPresult (*ReleaseReadBuffer)(CPhandle hContent, CPbyte *pBuffer); - - /** Write data of the specified size to the content (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency writes. */ - CPresult (*Write)( CPhandle hContent, CPbyte *data, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe used to write data to the content. - Client will fill buffer with output data. Note: pipe provides pointer. This function is appropriate - for large writes. The client must call WriteBuffer when done it has filled the buffer with data.*/ - CPresult (*GetWriteBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint nSize); - - /** Deliver a buffer obtained via GetWriteBuffer to the pipe. Pipe will write the - the contents of the buffer to content and advance content pointer by the size of the buffer */ - CPresult (*WriteBuffer)( CPhandle hContent, CPbyte *pBuffer, CPuint nFilledSize); - - /** Register a per-handle client callback with the content pipe. */ - CPresult (*RegisterCallback)( CPhandle hContent, CPresult (*ClientCallback)(CP_EVENTTYPE eEvent, CPuint iParam)); - -} CP_PIPETYPE; - -#endif - diff --git a/third_party/openmax/include/OMX_Core.h b/third_party/openmax/include/OMX_Core.h deleted file mode 100644 index 52d211f0dc..0000000000 --- a/third_party/openmax/include/OMX_Core.h +++ /dev/null @@ -1,1440 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Core.h - OpenMax IL version 1.1.2 - * The OMX_Core header file contains the definitions used by both the - * application and the component to access common items. - */ - -#ifndef OMX_Core_h -#define OMX_Core_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** The OMX_COMMANDTYPE enumeration is used to specify the action in the - * OMX_SendCommand macro. - * @ingroup core - */ -typedef enum OMX_COMMANDTYPE -{ - OMX_CommandStateSet, /**< Change the component state */ - OMX_CommandFlush, /**< Flush the data queue(s) of a component */ - OMX_CommandPortDisable, /**< Disable a port on a component. */ - OMX_CommandPortEnable, /**< Enable a port on a component. */ - OMX_CommandMarkBuffer, /**< Mark a component/buffer for observation */ - OMX_CommandKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_CommandVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_CommandMax = 0X7FFFFFFF -} OMX_COMMANDTYPE; - - - -/** The OMX_STATETYPE enumeration is used to indicate or change the component - * state. This enumeration reflects the current state of the component when - * used with the OMX_GetState macro or becomes the parameter in a state change - * command when used with the OMX_SendCommand macro. - * - * The component will be in the Loaded state after the component is initially - * loaded into memory. In the Loaded state, the component is not allowed to - * allocate or hold resources other than to build it's internal parameter - * and configuration tables. The application will send one or more - * SetParameters/GetParameters and SetConfig/GetConfig commands to the - * component and the component will record each of these parameter and - * configuration changes for use later. When the application sends the - * Idle command, the component will acquire the resources needed for the - * specified configuration and will transition to the idle state if the - * allocation is successful. If the component cannot successfully - * transition to the idle state for any reason, the state of the component - * shall be fully rolled back to the Loaded state (e.g. all allocated - * resources shall be released). When the component receives the command - * to go to the Executing state, it shall begin processing buffers by - * sending all input buffers it holds to the application. While - * the component is in the Idle state, the application may also send the - * Pause command. If the component receives the pause command while in the - * Idle state, the component shall send all input buffers it holds to the - * application, but shall not begin processing buffers. This will allow the - * application to prefill buffers. - * - * @ingroup comp - */ - -typedef enum OMX_STATETYPE -{ - OMX_StateInvalid, /**< component has detected that it's internal data - structures are corrupted to the point that - it cannot determine it's state properly */ - OMX_StateLoaded, /**< component has been loaded but has not completed - initialization. The OMX_SetParameter macro - and the OMX_GetParameter macro are the only - valid macros allowed to be sent to the - component in this state. */ - OMX_StateIdle, /**< component initialization has been completed - successfully and the component is ready to - to start. */ - OMX_StateExecuting, /**< component has accepted the start command and - is processing data (if data is available) */ - OMX_StatePause, /**< component has received pause command */ - OMX_StateWaitForResources, /**< component is waiting for resources, either after - preemption or before it gets the resources requested. - See specification for complete details. */ - OMX_StateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_StateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_StateMax = 0X7FFFFFFF -} OMX_STATETYPE; - -/** The OMX_ERRORTYPE enumeration defines the standard OMX Errors. These - * errors should cover most of the common failure cases. However, - * vendors are free to add additional error messages of their own as - * long as they follow these rules: - * 1. Vendor error messages shall be in the range of 0x90000000 to - * 0x9000FFFF. - * 2. Vendor error messages shall be defined in a header file provided - * with the component. No error messages are allowed that are - * not defined. - */ -typedef enum OMX_ERRORTYPE -{ - OMX_ErrorNone = 0, - - /** There were insufficient resources to perform the requested operation */ - OMX_ErrorInsufficientResources = (OMX_S32) 0x80001000, - - /** There was an error, but the cause of the error could not be determined */ - OMX_ErrorUndefined = (OMX_S32) 0x80001001, - - /** The component name string was not valid */ - OMX_ErrorInvalidComponentName = (OMX_S32) 0x80001002, - - /** No component with the specified name string was found */ - OMX_ErrorComponentNotFound = (OMX_S32) 0x80001003, - - /** The component specified did not have a "OMX_ComponentInit" or - "OMX_ComponentDeInit entry point */ - OMX_ErrorInvalidComponent = (OMX_S32) 0x80001004, - - /** One or more parameters were not valid */ - OMX_ErrorBadParameter = (OMX_S32) 0x80001005, - - /** The requested function is not implemented */ - OMX_ErrorNotImplemented = (OMX_S32) 0x80001006, - - /** The buffer was emptied before the next buffer was ready */ - OMX_ErrorUnderflow = (OMX_S32) 0x80001007, - - /** The buffer was not available when it was needed */ - OMX_ErrorOverflow = (OMX_S32) 0x80001008, - - /** The hardware failed to respond as expected */ - OMX_ErrorHardware = (OMX_S32) 0x80001009, - - /** The component is in the state OMX_StateInvalid */ - OMX_ErrorInvalidState = (OMX_S32) 0x8000100A, - - /** Stream is found to be corrupt */ - OMX_ErrorStreamCorrupt = (OMX_S32) 0x8000100B, - - /** Ports being connected are not compatible */ - OMX_ErrorPortsNotCompatible = (OMX_S32) 0x8000100C, - - /** Resources allocated to an idle component have been - lost resulting in the component returning to the loaded state */ - OMX_ErrorResourcesLost = (OMX_S32) 0x8000100D, - - /** No more indicies can be enumerated */ - OMX_ErrorNoMore = (OMX_S32) 0x8000100E, - - /** The component detected a version mismatch */ - OMX_ErrorVersionMismatch = (OMX_S32) 0x8000100F, - - /** The component is not ready to return data at this time */ - OMX_ErrorNotReady = (OMX_S32) 0x80001010, - - /** There was a timeout that occurred */ - OMX_ErrorTimeout = (OMX_S32) 0x80001011, - - /** This error occurs when trying to transition into the state you are already in */ - OMX_ErrorSameState = (OMX_S32) 0x80001012, - - /** Resources allocated to an executing or paused component have been - preempted, causing the component to return to the idle state */ - OMX_ErrorResourcesPreempted = (OMX_S32) 0x80001013, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the allocation of buffers (on a transition from the LOADED to the IDLE state or - on a port restart) when it deems that it has waited an unusually long time for the supplier - to send it an allocated buffer via a UseBuffer call. */ - OMX_ErrorPortUnresponsiveDuringAllocation = (OMX_S32) 0x80001014, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the deallocation of buffers (on a transition from the IDLE to LOADED state or - on a port stop) when it deems that it has waited an unusually long time for the supplier - to request the deallocation of a buffer header via a FreeBuffer call. */ - OMX_ErrorPortUnresponsiveDuringDeallocation = (OMX_S32) 0x80001015, - - /** A supplier port sends this error to the IL client (via the EventHandler callback) - during the stopping of a port (either on a transition from the IDLE to LOADED - state or a port stop) when it deems that it has waited an unusually long time for - the non-supplier to return a buffer via an EmptyThisBuffer or FillThisBuffer call. */ - OMX_ErrorPortUnresponsiveDuringStop = (OMX_S32) 0x80001016, - - /** Attempting a state transtion that is not allowed */ - OMX_ErrorIncorrectStateTransition = (OMX_S32) 0x80001017, - - /* Attempting a command that is not allowed during the present state. */ - OMX_ErrorIncorrectStateOperation = (OMX_S32) 0x80001018, - - /** The values encapsulated in the parameter or config structure are not supported. */ - OMX_ErrorUnsupportedSetting = (OMX_S32) 0x80001019, - - /** The parameter or config indicated by the given index is not supported. */ - OMX_ErrorUnsupportedIndex = (OMX_S32) 0x8000101A, - - /** The port index supplied is incorrect. */ - OMX_ErrorBadPortIndex = (OMX_S32) 0x8000101B, - - /** The port has lost one or more of its buffers and it thus unpopulated. */ - OMX_ErrorPortUnpopulated = (OMX_S32) 0x8000101C, - - /** Component suspended due to temporary loss of resources */ - OMX_ErrorComponentSuspended = (OMX_S32) 0x8000101D, - - /** Component suspended due to an inability to acquire dynamic resources */ - OMX_ErrorDynamicResourcesUnavailable = (OMX_S32) 0x8000101E, - - /** When the macroblock error reporting is enabled the component returns new error - for every frame that has errors */ - OMX_ErrorMbErrorsInFrame = (OMX_S32) 0x8000101F, - - /** A component reports this error when it cannot parse or determine the format of an input stream. */ - OMX_ErrorFormatNotDetected = (OMX_S32) 0x80001020, - - /** The content open operation failed. */ - OMX_ErrorContentPipeOpenFailed = (OMX_S32) 0x80001021, - - /** The content creation operation failed. */ - OMX_ErrorContentPipeCreationFailed = (OMX_S32) 0x80001022, - - /** Separate table information is being used */ - OMX_ErrorSeperateTablesUsed = (OMX_S32) 0x80001023, - - /** Tunneling is unsupported by the component*/ - OMX_ErrorTunnelingUnsupported = (OMX_S32) 0x80001024, - - OMX_ErrorKhronosExtensions = (OMX_S32)0x8F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ErrorVendorStartUnused = (OMX_S32)0x90000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ErrorMax = 0x7FFFFFFF -} OMX_ERRORTYPE; - -/** @ingroup core */ -typedef OMX_ERRORTYPE (* OMX_COMPONENTINITTYPE)(OMX_IN OMX_HANDLETYPE hComponent); - -/** @ingroup core */ -typedef struct OMX_COMPONENTREGISTERTYPE -{ - const char * pName; /* Component name, 128 byte limit (including '\0') applies */ - OMX_COMPONENTINITTYPE pInitialize; /* Component instance initialization function */ -} OMX_COMPONENTREGISTERTYPE; - -/** @ingroup core */ -extern OMX_COMPONENTREGISTERTYPE OMX_ComponentRegistered[]; - -/** @ingroup rpm */ -typedef struct OMX_PRIORITYMGMTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nGroupPriority; /**< Priority of the component group */ - OMX_U32 nGroupID; /**< ID of the component group */ -} OMX_PRIORITYMGMTTYPE; - -/* Component name and Role names are limited to 128 characters including the terminating '\0'. */ -#define OMX_MAX_STRINGNAME_SIZE 128 - -/** @ingroup comp */ -typedef struct OMX_PARAM_COMPONENTROLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 cRole[OMX_MAX_STRINGNAME_SIZE]; /**< name of standard component which defines component role */ -} OMX_PARAM_COMPONENTROLETYPE; - -/** End of Stream Buffer Flag: - * - * A component sets EOS when it has no more data to emit on a particular - * output port. Thus an output port shall set EOS on the last buffer it - * emits. A component's determination of when an output port should - * cease sending data is implemenation specific. - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_EOS 0x00000001 - -/** Start Time Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the STARTTIME - * flag on the buffer that contains the starting timestamp for the - * stream. The starting timestamp corresponds to the first data that - * should be displayed at startup or after a seek. - * The first timestamp of the stream is not necessarily the start time. - * For instance, in the case of a seek to a particular video frame, - * the target frame may be an interframe. Thus the first buffer of - * the stream will be the intra-frame preceding the target frame and - * the starttime will occur with the target frame (with any other - * required frames required to reconstruct the target intervening). - * - * The STARTTIME flag is directly associated with the buffer's - * timestamp ' thus its association to buffer data and its - * propagation is identical to the timestamp's. - * - * When a Sync Component client receives a buffer with the - * STARTTIME flag it shall perform a SetConfig on its sync port - * using OMX_ConfigTimeClientStartTime and passing the buffer's - * timestamp. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_STARTTIME 0x00000002 - - - -/** Decode Only Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the DECODEONLY - * flag on any buffer that should shall be decoded but should not be - * displayed. This flag is used, for instance, when a source seeks to - * a target interframe that requires the decode of frames preceding the - * target to facilitate the target's reconstruction. In this case the - * source would emit the frames preceding the target downstream - * but mark them as decode only. - * - * The DECODEONLY is associated with buffer data and propagated in a - * manner identical to the buffer timestamp. - * - * A component that renders data should ignore all buffers with - * the DECODEONLY flag set. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DECODEONLY 0x00000004 - - -/* Data Corrupt Flag: This flag is set when the IL client believes the data in the associated buffer is corrupt - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DATACORRUPT 0x00000008 - -/* End of Frame: The buffer contains exactly one end of frame and no data - * occurs after the end of frame. This flag is an optional hint. The absence - * of this flag does not imply the absence of an end of frame within the buffer. - * @ingroup buf -*/ -#define OMX_BUFFERFLAG_ENDOFFRAME 0x00000010 - -/* Sync Frame Flag: This flag is set when the buffer content contains a coded sync frame ' - * a frame that has no dependency on any other frame information - * @ingroup buf - */ -#define OMX_BUFFERFLAG_SYNCFRAME 0x00000020 - -/* Extra data present flag: there is extra data appended to the data stream - * residing in the buffer - * @ingroup buf - */ -#define OMX_BUFFERFLAG_EXTRADATA 0x00000040 - -/** Codec Config Buffer Flag: -* OMX_BUFFERFLAG_CODECCONFIG is an optional flag that is set by an -* output port when all bytes in the buffer form part or all of a set of -* codec specific configuration data. Examples include SPS/PPS nal units -* for OMX_VIDEO_CodingAVC or AudioSpecificConfig data for -* OMX_AUDIO_CodingAAC. Any component that for a given stream sets -* OMX_BUFFERFLAG_CODECCONFIG shall not mix codec configuration bytes -* with frame data in the same buffer, and shall send all buffers -* containing codec configuration bytes before any buffers containing -* frame data that those configurations bytes describe. -* If the stream format for a particular codec has a frame specific -* header at the start of each frame, for example OMX_AUDIO_CodingMP3 or -* OMX_AUDIO_CodingAAC in ADTS mode, then these shall be presented as -* normal without setting OMX_BUFFERFLAG_CODECCONFIG. - * @ingroup buf - */ -#define OMX_BUFFERFLAG_CODECCONFIG 0x00000080 - -/* -* OMX_BUFFERFLAG_READONLY: This flag is set when a component emitting the -* buffer on an output port or the IL client wishes to identify the buffer -* payload contents to be read-only. An IL client or an input port -* shall not alter the contents of the buffer. This flag shall only be -* cleared by the originator of the buffer when the buffer is returned. -* For tunneled ports, the usage of this flag shall be allowed only if the -* components negotiated a read-only tunnel -*/ -#define OMX_BUFFERFLAG_READONLY 0x00000200 - -/** @ingroup buf */ -typedef struct OMX_BUFFERHEADERTYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8* pBuffer; /**< Pointer to actual block of memory - that is acting as the buffer */ - OMX_U32 nAllocLen; /**< size of the buffer allocated, in bytes */ - OMX_U32 nFilledLen; /**< number of bytes currently in the - buffer */ - OMX_U32 nOffset; /**< start offset of valid data in bytes from - the start of the buffer */ - OMX_PTR pAppPrivate; /**< pointer to any data the application - wants to associate with this buffer */ - OMX_PTR pPlatformPrivate; /**< pointer to any data the platform - wants to associate with this buffer */ - OMX_PTR pInputPortPrivate; /**< pointer to any data the input port - wants to associate with this buffer */ - OMX_PTR pOutputPortPrivate; /**< pointer to any data the output port - wants to associate with this buffer */ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will generate a - mark event upon processing this buffer. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ - OMX_U32 nTickCount; /**< Optional entry that the component and - application can update with a tick count - when they access the component. This - value should be in microseconds. Since - this is a value relative to an arbitrary - starting point, this value cannot be used - to determine absolute time. This is an - optional entry and not all components - will update it.*/ - OMX_TICKS nTimeStamp; /**< Timestamp corresponding to the sample - starting at the first logical sample - boundary in the buffer. Timestamps of - successive samples within the buffer may - be inferred by adding the duration of the - of the preceding buffer to the timestamp - of the preceding buffer.*/ - OMX_U32 nFlags; /**< buffer specific flags */ - OMX_U32 nOutputPortIndex; /**< The index of the output port (if any) using - this buffer */ - OMX_U32 nInputPortIndex; /**< The index of the input port (if any) using - this buffer */ -} OMX_BUFFERHEADERTYPE; - -/** The OMX_EXTRADATATYPE enumeration is used to define the - * possible extra data payload types. - * NB: this enum is binary backwards compatible with the previous - * OMX_EXTRADATA_QUANT define. This should be replaced with - * OMX_ExtraDataQuantization. - */ -typedef enum OMX_EXTRADATATYPE -{ - OMX_ExtraDataNone = 0, /**< Indicates that no more extra data sections follow */ - OMX_ExtraDataQuantization, /**< The data payload contains quantization data */ - OMX_ExtraDataKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ExtraDataVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ExtraDataMax = 0x7FFFFFFF -} OMX_EXTRADATATYPE; - - -typedef struct OMX_OTHER_EXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_EXTRADATATYPE eType; /* Extra Data type */ - OMX_U32 nDataSize; /* Size of the supporting data to follow */ - OMX_U8 data[1]; /* Supporting data hint */ -} OMX_OTHER_EXTRADATATYPE; - -/** @ingroup comp */ -typedef struct OMX_PORT_PARAM_TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPorts; /**< The number of ports for this component */ - OMX_U32 nStartPortNumber; /** first port number for this type of port */ -} OMX_PORT_PARAM_TYPE; - -/** @ingroup comp */ -typedef enum OMX_EVENTTYPE -{ - OMX_EventCmdComplete, /**< component has sucessfully completed a command */ - OMX_EventError, /**< component has detected an error condition */ - OMX_EventMark, /**< component has detected a buffer mark */ - OMX_EventPortSettingsChanged, /**< component is reported a port settings change */ - OMX_EventBufferFlag, /**< component has detected an EOS */ - OMX_EventResourcesAcquired, /**< component has been granted resources and is - automatically starting the state change from - OMX_StateWaitForResources to OMX_StateIdle. */ - OMX_EventComponentResumed, /**< Component resumed due to reacquisition of resources */ - OMX_EventDynamicResourcesAvailable, /**< Component has acquired previously unavailable dynamic resources */ - OMX_EventPortFormatDetected, /**< Component has detected a supported format. */ - OMX_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_EventMax = 0x7FFFFFFF -} OMX_EVENTTYPE; - -typedef struct OMX_CALLBACKTYPE -{ - /** The EventHandler method is used to notify the application when an - event of interest occurs. Events are defined in the OMX_EVENTTYPE - enumeration. Please see that enumeration for details of what will - be returned for each type of event. Callbacks should not return - an error to the component, so if an error occurs, the application - shall handle it internally. This is a blocking call. - - The application should return from this call within 5 msec to avoid - blocking the component for an excessively long period of time. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param eEvent - Event that the component wants to notify the application about. - @param nData1 - nData will be the OMX_ERRORTYPE for an error event and will be - an OMX_COMMANDTYPE for a command complete event and OMX_INDEXTYPE for a OMX_PortSettingsChanged event. - @param nData2 - nData2 will hold further information related to the event. Can be OMX_STATETYPE for - a OMX_CommandStateSet command or port index for a OMX_PortSettingsChanged event. - Default value is 0 if not used. ) - @param pEventData - Pointer to additional event-specific data (see spec for meaning). - */ - - OMX_ERRORTYPE (*EventHandler)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_EVENTTYPE eEvent, - OMX_IN OMX_U32 nData1, - OMX_IN OMX_U32 nData2, - OMX_IN OMX_PTR pEventData); - - /** The EmptyBufferDone method is used to return emptied buffers from an - input port back to the application for reuse. This is a blocking call - so the application should not attempt to refill the buffers during this - call, but should queue them and refill them in another thread. There - is no error return, so the application shall handle any errors generated - internally. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was emptied. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyBufferDone)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The FillBufferDone method is used to return filled buffers from an - output port back to the application for emptying and then reuse. - This is a blocking call so the application should not attempt to - empty the buffers during this call, but should queue the buffers - and empty them in another thread. There is no error return, so - the application shall handle any errors generated internally. The - application shall also update the buffer header to indicate the - number of bytes placed into the buffer. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was filled. - @ingroup buf - */ - OMX_ERRORTYPE (*FillBufferDone)( - OMX_OUT OMX_HANDLETYPE hComponent, - OMX_OUT OMX_PTR pAppData, - OMX_OUT OMX_BUFFERHEADERTYPE* pBuffer); - -} OMX_CALLBACKTYPE; - -/** The OMX_BUFFERSUPPLIERTYPE enumeration is used to dictate port supplier - preference when tunneling between two ports. - @ingroup tun buf -*/ -typedef enum OMX_BUFFERSUPPLIERTYPE -{ - OMX_BufferSupplyUnspecified = 0x0, /**< port supplying the buffers is unspecified, - or don't care */ - OMX_BufferSupplyInput, /**< input port supplies the buffers */ - OMX_BufferSupplyOutput, /**< output port supplies the buffers */ - OMX_BufferSupplyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_BufferSupplyVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_BufferSupplyMax = 0x7FFFFFFF -} OMX_BUFFERSUPPLIERTYPE; - - -/** buffer supplier parameter - * @ingroup tun - */ -typedef struct OMX_PARAM_BUFFERSUPPLIERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BUFFERSUPPLIERTYPE eBufferSupplier; /**< buffer supplier */ -} OMX_PARAM_BUFFERSUPPLIERTYPE; - - -/**< indicates that buffers received by an input port of a tunnel - may not modify the data in the buffers - @ingroup tun - */ -#define OMX_PORTTUNNELFLAG_READONLY 0x00000001 - - -/** The OMX_TUNNELSETUPTYPE structure is used to pass data from an output - port to an input port as part the two ComponentTunnelRequest calls - resulting from a OMX_SetupTunnel call from the IL Client. - @ingroup tun - */ -typedef struct OMX_TUNNELSETUPTYPE -{ - OMX_U32 nTunnelFlags; /**< bit flags for tunneling */ - OMX_BUFFERSUPPLIERTYPE eSupplier; /**< supplier preference */ -} OMX_TUNNELSETUPTYPE; - -/* OMX Component headers is included to enable the core to use - macros for functions into the component for OMX release 1.0. - Developers should not access any structures or data from within - the component header directly */ -/* TO BE REMOVED - #include */ - -/** GetComponentVersion will return information about the component. - This is a blocking call. This macro will go directly from the - application to the component (via a core macro). The - component will return from this call within 5 msec. - @param [in] hComponent - handle of component to execute the command - @param [out] pComponentName - pointer to an empty string of length 128 bytes. The component - will write its name into this string. The name will be - terminated by a single zero byte. The name of a component will - be 127 bytes or less to leave room for the trailing zero byte. - An example of a valid component name is "OMX.ABC.ChannelMixer\0". - @param [out] pComponentVersion - pointer to an OMX Version structure that the component will fill - in. The component will fill in a value that indicates the - component version. NOTE: the component version is NOT the same - as the OMX Specification version (found in all structures). The - component version is defined by the vendor of the component and - its value is entirely up to the component vendor. - @param [out] pSpecVersion - pointer to an OMX Version structure that the component will fill - in. The SpecVersion is the version of the specification that the - component was built against. Please note that this value may or - may not match the structure's version. For example, if the - component was built against the 2.0 specification, but the - application (which creates the structure is built against the - 1.0 specification the versions would be different. - @param [out] pComponentUUID - pointer to the UUID of the component which will be filled in by - the component. The UUID is a unique identifier that is set at - RUN time for the component and is unique to each instantion of - the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) /* Macro End */ - - -/** Send a command to the component. This call is a non-blocking call. - The component should check the parameters and then queue the command - to the component thread to be executed. The component thread shall - send the EventHandler() callback at the conclusion of the command. - This macro will go directly from the application to the component (via - a core macro). The component will return from this call within 5 msec. - - When the command is "OMX_CommandStateSet" the component will queue a - state transition to the new state idenfied in nParam. - - When the command is "OMX_CommandFlush", to flush a port's buffer queues, - the command will force the component to return all buffers NOT CURRENTLY - BEING PROCESSED to the application, in the order in which the buffers - were received. - - When the command is "OMX_CommandPortDisable" or - "OMX_CommandPortEnable", the component's port (given by the value of - nParam) will be stopped or restarted. - - When the command "OMX_CommandMarkBuffer" is used to mark a buffer, the - pCmdData will point to a OMX_MARKTYPE structure containing the component - handle of the component to examine the buffer chain for the mark. nParam1 - contains the index of the port on which the buffer mark is applied. - - Specification text for more details. - - @param [in] hComponent - handle of component to execute the command - @param [in] Cmd - Command for the component to execute - @param [in] nParam - Parameter for the command to be executed. When Cmd has the value - OMX_CommandStateSet, value is a member of OMX_STATETYPE. When Cmd has - the value OMX_CommandFlush, value of nParam indicates which port(s) - to flush. -1 is used to flush all ports a single port index will - only flush that port. When Cmd has the value "OMX_CommandPortDisable" - or "OMX_CommandPortEnable", the component's port is given by - the value of nParam. When Cmd has the value "OMX_CommandMarkBuffer" - the components pot is given by the value of nParam. - @param [in] pCmdData - Parameter pointing to the OMX_MARKTYPE structure when Cmd has the value - "OMX_CommandMarkBuffer". - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) \ - ((OMX_COMPONENTTYPE*)hComponent)->SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) /* Macro End */ - - -/** The OMX_GetParameter macro will get one of the current parameter - settings from the component. This macro cannot only be invoked when - the component is in the OMX_StateInvalid state. The nParamIndex - parameter is used to indicate which structure is being requested from - the component. The application shall allocate the correct structure - and shall fill in the structure size and version information before - invoking this macro. When the parameter applies to a port, the - caller shall fill in the appropriate nPortIndex value indicating the - port on which the parameter applies. If the component has not had - any settings changed, then the component should return a set of - valid DEFAULT parameters for the component. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nParamIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentParameterStructure - Pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_SetParameter macro will send an initialization parameter - structure to a component. Each structure shall be sent one at a time, - in a separate invocation of the macro. This macro can only be - invoked when the component is in the OMX_StateLoaded state, or the - port is disabled (when the parameter applies to a port). The - nParamIndex parameter is used to indicate which structure is being - passed to the component. The application shall allocate the - correct structure and shall fill in the structure size and version - information (as well as the actual data) before invoking this macro. - The application is free to dispose of this structure after the call - as the component is required to copy any data it shall retain. This - is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration. - @param [in] pComponentParameterStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_GetConfig macro will get one of the configuration structures - from a component. This macro can be invoked anytime after the - component has been loaded. The nParamIndex call parameter is used to - indicate which structure is being requested from the component. The - application shall allocate the correct structure and shall fill in the - structure size and version information before invoking this macro. - If the component has not had this configuration parameter sent before, - then the component should return a set of valid DEFAULT values for the - component. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentConfigStructure - pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp -*/ -#define OMX_GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_SetConfig macro will send one of the configuration - structures to a component. Each structure shall be sent one at a time, - each in a separate invocation of the macro. This macro can be invoked - anytime after the component has been loaded. The application shall - allocate the correct structure and shall fill in the structure size - and version information (as well as the actual data) before invoking - this macro. The application is free to dispose of this structure after - the call as the component is required to copy any data it shall retain. - This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nConfigIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration above. - @param [in] pComponentConfigStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_GetExtensionIndex macro will invoke a component to translate - a vendor specific configuration or parameter string into an OMX - structure index. There is no requirement for the vendor to support - this command for the indexes already found in the OMX_INDEXTYPE - enumeration (this is done to save space in small components). The - component shall support all vendor supplied extension indexes not found - in the master OMX_INDEXTYPE enumeration. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] cParameterName - OMX_STRING that shall be less than 128 characters long including - the trailing null byte. This is the string that will get - translated by the component into a configuration index. - @param [out] pIndexType - a pointer to a OMX_INDEXTYPE to receive the index value. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) /* Macro End */ - - -/** The OMX_GetState macro will invoke the component to get the current - state of the component and place the state value into the location - pointed to by pState. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] pState - pointer to the location to receive the state. The value returned - is one of the OMX_STATETYPE members - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetState( \ - hComponent, \ - pState) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetState( \ - hComponent, \ - pState) /* Macro End */ - - -/** The OMX_UseBuffer macro will request that the component use - a buffer (and allocate its own buffer header) already allocated - by another component, or by the IL Client. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ - -#define OMX_UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) - - -/** The OMX_AllocateBuffer macro will request that the component allocate - a new buffer and buffer header. The component will allocate the - buffer and the buffer header and return a pointer to the buffer - header. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive - the pointer to the buffer header - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] nSizeBytes - size of the buffer to allocate. Used when bAllocateNew is true. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) \ - ((OMX_COMPONENTTYPE*)hComponent)->AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) /* Macro End */ - - -/** The OMX_FreeBuffer macro will release a buffer header from the component - which was allocated using either OMX_AllocateBuffer or OMX_UseBuffer. If - the component allocated the buffer (see the OMX_UseBuffer macro) then - the component shall free the buffer and buffer header. This is a - blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) /* Macro End */ - - -/** The OMX_EmptyThisBuffer macro will send a buffer full of data to an - input port of a component. The buffer will be emptied by the component - and returned to the application via the EmptyBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then empty the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_StateExecuting. If nPortIndex does not specify an input - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_EmptyThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->EmptyThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - -/** The OMX_FillThisBuffer macro will send an empty buffer to an - output port of a component. The buffer will be filled by the component - and returned to the application via the FillBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then fill the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_ExecutingState. If nPortIndex does not specify an output - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FillThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FillThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - - -/** The OMX_UseEGLImage macro will request that the component use - a EGLImage provided by EGL (and allocate its own buffer header) - This is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header. Note that the memory location used - for this buffer is NOT visible to the IL Client. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] eglImage - eglImage contains the handle of the EGLImage to use as a buffer on the - specified port. The component is expected to validate properties of - the EGLImage against the configuration of the port to ensure the component - can use the EGLImage as a buffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) - -/** The OMX_Init method is used to initialize the OMX core. It shall be the - first call made into OMX and it should only be executed one time without - an interviening OMX_Deinit call. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Init(void); - - -/** The OMX_Deinit method is used to deinitialize the OMX core. It shall be - the last call made into OMX. In the event that the core determines that - thare are components loaded when this call is made, the core may return - with an error rather than try to unload the components. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Deinit(void); - - -/** The OMX_ComponentNameEnum method will enumerate through all the names of - recognised valid components in the system. This function is provided - as a means to detect all the components in the system run-time. There is - no strict ordering to the enumeration order of component names, although - each name will only be enumerated once. If the OMX core supports run-time - installation of new components, it is only requried to detect newly - installed components when the first call to enumerate component names - is made (i.e. when nIndex is 0x0). - - The core should return from this call in 20 msec. - - @param [out] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] nNameLength - number of characters in the cComponentName string. With all - component name strings restricted to less than 128 characters - (including the trailing null) it is recomended that the caller - provide a input string for the cComponentName of 128 characters. - @param [in] nIndex - number containing the enumeration index for the component. - Multiple calls to OMX_ComponentNameEnum with increasing values - of nIndex will enumerate through the component names in the - system until OMX_ErrorNoMore is returned. The value of nIndex - is 0 to (N-1), where N is the number of valid installed components - in the system. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. When the value of nIndex exceeds the number of - components in the system minus 1, OMX_ErrorNoMore will be - returned. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_ComponentNameEnum( - OMX_OUT OMX_STRING cComponentName, - OMX_IN OMX_U32 nNameLength, - OMX_IN OMX_U32 nIndex); - - -/** The OMX_GetHandle method will locate the component specified by the - component name given, load that component into memory and then invoke - the component's methods to create an instance of the component. - - The core should return from this call within 20 msec. - - @param [out] pHandle - pointer to an OMX_HANDLETYPE pointer to be filled in by this method. - @param [in] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] pAppData - pointer to an application defined value that will be returned - during callbacks so that the application can identify the source - of the callback. - @param [in] pCallBacks - pointer to a OMX_CALLBACKTYPE structure that will be passed to the - component to initialize it with. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_GetHandle( - OMX_OUT OMX_HANDLETYPE* pHandle, - OMX_IN OMX_STRING cComponentName, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_CALLBACKTYPE* pCallBacks); - - -/** The OMX_FreeHandle method will free a handle allocated by the OMX_GetHandle - method. If the component reference count goes to zero, the component will - be unloaded from memory. - - The core should return from this call within 20 msec when the component is - in the OMX_StateLoaded state. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_FreeHandle( - OMX_IN OMX_HANDLETYPE hComponent); - - - -/** The OMX_SetupTunnel method will handle the necessary calls to the components - to setup the specified tunnel the two components. NOTE: This is - an actual method (not a #define macro). This method will make calls into - the component ComponentTunnelRequest method to do the actual tunnel - connection. - - The ComponentTunnelRequest method on both components will be called. - This method shall not be called unless the component is in the - OMX_StateLoaded state except when the ports used for the tunnel are - disabled. In this case, the component may be in the OMX_StateExecuting, - OMX_StatePause, or OMX_StateIdle states. - - The core should return from this call within 20 msec. - - @param [in] hOutput - Handle of the component to be accessed. Also this is the handle - of the component whose port, specified in the nPortOutput parameter - will be used the source for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hOutput be the source for the data when - tunelling (i.e. nPortOutput is an output port). If 0x0, the component - specified in hInput will have it's port specified in nPortInput - setup for communication with the application / IL client. - @param [in] nPortOutput - nPortOutput is used to select the source port on component to be - used in the tunnel. - @param [in] hInput - This is the component to setup the tunnel with. This is the handle - of the component whose port, specified in the nPortInput parameter - will be used the destination for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hInput be the destination for the data when - tunelling (i.e. nPortInut is an input port). If 0x0, the component - specified in hOutput will have it's port specified in nPortPOutput - setup for communication with the application / IL client. - @param [in] nPortInput - nPortInput is used to select the destination port on component to be - used in the tunnel. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - When OMX_ErrorNotImplemented is returned, one or both components is - a non-interop component and does not support tunneling. - - On failure, the ports of both components are setup for communication - with the application / IL Client. - @ingroup core tun - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_SetupTunnel( - OMX_IN OMX_HANDLETYPE hOutput, - OMX_IN OMX_U32 nPortOutput, - OMX_IN OMX_HANDLETYPE hInput, - OMX_IN OMX_U32 nPortInput); - -/** @ingroup cp */ -OMX_API OMX_ERRORTYPE OMX_GetContentPipe( - OMX_OUT OMX_HANDLETYPE *hPipe, - OMX_IN OMX_STRING szURI); - -/** The OMX_GetComponentsOfRole method will return the number of components that support the given - role and (if the compNames field is non-NULL) the names of those components. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the compNames field NULL to determine the number of component names - * second call this function with the compNames field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] role - This is generic standard component name consisting only of component class - name and the type within that class (e.g. 'audio_decoder.aac'). - @param [inout] pNumComps - This is used both as input and output. - - If compNames is NULL, the input is ignored and the output specifies how many components support - the given role. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of components string names listed within the compNames parameter. - @param [inout] compNames - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings which accepts - a list of the names of all physical components that implement the specified standard component name. - Each name is NULL terminated. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetComponentsOfRole ( - OMX_IN OMX_STRING role, - OMX_INOUT OMX_U32 *pNumComps, - OMX_INOUT OMX_U8 **compNames); - -/** The OMX_GetRolesOfComponent method will return the number of roles supported by the given - component and (if the roles field is non-NULL) the names of those roles. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the roles field NULL to determine the number of role names - * second call this function with the roles field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] compName - This is the name of the component being queried about. - @param [inout] pNumRoles - This is used both as input and output. - - If roles is NULL, the input is ignored and the output specifies how many roles the component supports. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of roles string names listed within the roles parameter. - @param [out] roles - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings - which accepts a list of the names of all standard components roles implemented on the - specified component name. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetRolesOfComponent ( - OMX_IN OMX_STRING compName, - OMX_INOUT OMX_U32 *pNumRoles, - OMX_OUT OMX_U8 **roles); - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_CoreExt.h b/third_party/openmax/include/OMX_CoreExt.h deleted file mode 100644 index 3ec14b05f3..0000000000 --- a/third_party/openmax/include/OMX_CoreExt.h +++ /dev/null @@ -1,66 +0,0 @@ -/* - * Copyright (c) 2009 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_CoreExt.h - OpenMax IL version 1.1.2 - * The OMX_CoreExt header file contains extensions to the definitions used - * by both the application and the component to access common items. - */ - -#ifndef OMX_CoreExt_h -#define OMX_CoreExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** Event type extensions. */ -typedef enum OMX_EVENTEXTTYPE -{ - OMX_EventIndexSettingChanged = OMX_EventKhronosExtensions, /**< component signals the IL client of a change - in a param, config, or extension */ - OMX_EventExtMax = 0x7FFFFFFF -} OMX_EVENTEXTTYPE; - - -/** Enable or disable a callback event. */ -typedef struct OMX_CONFIG_CALLBACKREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_INDEXTYPE nIndex; /**< the index the callback is requested for */ - OMX_BOOL bEnable; /**< enable (OMX_TRUE) or disable (OMX_FALSE) the callback */ -} OMX_CONFIG_CALLBACKREQUESTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_CoreExt_h */ -/* File EOF */ diff --git a/third_party/openmax/include/OMX_IVCommon.h b/third_party/openmax/include/OMX_IVCommon.h deleted file mode 100644 index ec717565a0..0000000000 --- a/third_party/openmax/include/OMX_IVCommon.h +++ /dev/null @@ -1,933 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_IVCommon.h - OpenMax IL version 1.1.2 - * The structures needed by Video and Image components to exchange - * parameters and configuration data with the components. - */ -#ifndef OMX_IVCommon_h -#define OMX_IVCommon_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** - * Each OMX header must include all required header files to allow the header - * to compile without errors. The includes below are required for this header - * file to compile successfully - */ - -#include - -/** @defgroup iv OpenMAX IL Imaging and Video Domain - * Common structures for OpenMAX IL Imaging and Video domains - * @{ - */ - - -/** - * Enumeration defining possible uncompressed image/video formats. - * - * ENUMS: - * Unused : Placeholder value when format is N/A - * Monochrome : black and white - * 8bitRGB332 : Red 7:5, Green 4:2, Blue 1:0 - * 12bitRGB444 : Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB4444 : Alpha 15:12, Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB1555 : Alpha 15, Red 14:10, Green 9:5, Blue 4:0 - * 16bitRGB565 : Red 15:11, Green 10:5, Blue 4:0 - * 16bitBGR565 : Blue 15:11, Green 10:5, Red 4:0 - * 18bitRGB666 : Red 17:12, Green 11:6, Blue 5:0 - * 18bitARGB1665 : Alpha 17, Red 16:11, Green 10:5, Blue 4:0 - * 19bitARGB1666 : Alpha 18, Red 17:12, Green 11:6, Blue 5:0 - * 24bitRGB888 : Red 24:16, Green 15:8, Blue 7:0 - * 24bitBGR888 : Blue 24:16, Green 15:8, Red 7:0 - * 24bitARGB1887 : Alpha 23, Red 22:15, Green 14:7, Blue 6:0 - * 25bitARGB1888 : Alpha 24, Red 23:16, Green 15:8, Blue 7:0 - * 32bitBGRA8888 : Blue 31:24, Green 23:16, Red 15:8, Alpha 7:0 - * 32bitARGB8888 : Alpha 31:24, Red 23:16, Green 15:8, Blue 7:0 - * YUV411Planar : U,Y are subsampled by a factor of 4 horizontally - * YUV411PackedPlanar : packed per payload in planar slices - * YUV420Planar : Three arrays Y,U,V. - * YUV420PackedPlanar : packed per payload in planar slices - * YUV420SemiPlanar : Two arrays, one is all Y, the other is U and V - * YUV422Planar : Three arrays Y,U,V. - * YUV422PackedPlanar : packed per payload in planar slices - * YUV422SemiPlanar : Two arrays, one is all Y, the other is U and V - * YCbYCr : Organized as 16bit YUYV (i.e. YCbYCr) - * YCrYCb : Organized as 16bit YVYU (i.e. YCrYCb) - * CbYCrY : Organized as 16bit UYVY (i.e. CbYCrY) - * CrYCbY : Organized as 16bit VYUY (i.e. CrYCbY) - * YUV444Interleaved : Each pixel contains equal parts YUV - * RawBayer8bit : SMIA camera output format - * RawBayer10bit : SMIA camera output format - * RawBayer8bitcompressed : SMIA camera output format - */ -typedef enum OMX_COLOR_FORMATTYPE { - OMX_COLOR_FormatUnused, - OMX_COLOR_FormatMonochrome, - OMX_COLOR_Format8bitRGB332, - OMX_COLOR_Format12bitRGB444, - OMX_COLOR_Format16bitARGB4444, - OMX_COLOR_Format16bitARGB1555, - OMX_COLOR_Format16bitRGB565, - OMX_COLOR_Format16bitBGR565, - OMX_COLOR_Format18bitRGB666, - OMX_COLOR_Format18bitARGB1665, - OMX_COLOR_Format19bitARGB1666, - OMX_COLOR_Format24bitRGB888, - OMX_COLOR_Format24bitBGR888, - OMX_COLOR_Format24bitARGB1887, - OMX_COLOR_Format25bitARGB1888, - OMX_COLOR_Format32bitBGRA8888, - OMX_COLOR_Format32bitARGB8888, - OMX_COLOR_FormatYUV411Planar, - OMX_COLOR_FormatYUV411PackedPlanar, - OMX_COLOR_FormatYUV420Planar, - OMX_COLOR_FormatYUV420PackedPlanar, - OMX_COLOR_FormatYUV420SemiPlanar, - OMX_COLOR_FormatYUV422Planar, - OMX_COLOR_FormatYUV422PackedPlanar, - OMX_COLOR_FormatYUV422SemiPlanar, - OMX_COLOR_FormatYCbYCr, - OMX_COLOR_FormatYCrYCb, - OMX_COLOR_FormatCbYCrY, - OMX_COLOR_FormatCrYCbY, - OMX_COLOR_FormatYUV444Interleaved, - OMX_COLOR_FormatRawBayer8bit, - OMX_COLOR_FormatRawBayer10bit, - OMX_COLOR_FormatRawBayer8bitcompressed, - OMX_COLOR_FormatL2, - OMX_COLOR_FormatL4, - OMX_COLOR_FormatL8, - OMX_COLOR_FormatL16, - OMX_COLOR_FormatL24, - OMX_COLOR_FormatL32, - OMX_COLOR_FormatYUV420PackedSemiPlanar, - OMX_COLOR_FormatYUV422PackedSemiPlanar, - OMX_COLOR_Format18BitBGR666, - OMX_COLOR_Format24BitARGB6666, - OMX_COLOR_Format24BitABGR6666, - OMX_COLOR_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_COLOR_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - /** - -/** @defgroup imaging OpenMAX IL Imaging Domain - * @ingroup iv - * Structures for OpenMAX IL Imaging domain - * @{ - */ - -/** - * Enumeration used to define the possible image compression coding. - */ -typedef enum OMX_IMAGE_CODINGTYPE { - OMX_IMAGE_CodingUnused, /**< Value when format is N/A */ - OMX_IMAGE_CodingAutoDetect, /**< Auto detection of image format */ - OMX_IMAGE_CodingJPEG, /**< JPEG/JFIF image format */ - OMX_IMAGE_CodingJPEG2K, /**< JPEG 2000 image format */ - OMX_IMAGE_CodingEXIF, /**< EXIF image format */ - OMX_IMAGE_CodingTIFF, /**< TIFF image format */ - OMX_IMAGE_CodingGIF, /**< Graphics image format */ - OMX_IMAGE_CodingPNG, /**< PNG image format */ - OMX_IMAGE_CodingLZW, /**< LZW image format */ - OMX_IMAGE_CodingBMP, /**< Windows Bitmap format */ - OMX_IMAGE_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_CodingMax = 0x7FFFFFFF -} OMX_IMAGE_CODINGTYPE; - - -/** - * Data structure used to define an image path. The number of image paths - * for input and output will vary by type of the image component. - * - * Input (aka Source) : Zero Inputs, one Output, - * Splitter : One Input, 2 or more Outputs, - * Processing Element : One Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : One Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output - * image path. If additional vendor specific data is required, it should - * be transmitted to the component using the CustomCommand function. - * Compliant components will prepopulate this structure with optimal - * values during the OMX_GetParameter() command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nFrameHeight : Height of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nStride : Number of bytes per span of an image (i.e. - * indicates the number of bytes to get from - * span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of - * the component. When OMX_IMAGE_CodingUnused is - * specified, eColorFormat is valid - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_IMAGE_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_BOOL bFlagErrorConcealment; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_IMAGE_PORTDEFINITIONTYPE; - - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_IMAGE_CodingUnused is specified, - * eColorFormat is valid - * eColorFormat : Decompressed format used by this component - */ -typedef struct OMX_IMAGE_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; -} OMX_IMAGE_PARAM_PORTFORMATTYPE; - - -/** - * Flash control type - * - * ENUMS - * Torch : Flash forced constantly on - */ -typedef enum OMX_IMAGE_FLASHCONTROLTYPE { - OMX_IMAGE_FlashControlOn = 0, - OMX_IMAGE_FlashControlOff, - OMX_IMAGE_FlashControlAuto, - OMX_IMAGE_FlashControlRedEyeReduction, - OMX_IMAGE_FlashControlFillin, - OMX_IMAGE_FlashControlTorch, - OMX_IMAGE_FlashControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FlashControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FlashControlMax = 0x7FFFFFFF -} OMX_IMAGE_FLASHCONTROLTYPE; - - -/** - * Flash control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFlashControl : Flash control type - */ -typedef struct OMX_IMAGE_PARAM_FLASHCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FLASHCONTROLTYPE eFlashControl; -} OMX_IMAGE_PARAM_FLASHCONTROLTYPE; - - -/** - * Focus control type - */ -typedef enum OMX_IMAGE_FOCUSCONTROLTYPE { - OMX_IMAGE_FocusControlOn = 0, - OMX_IMAGE_FocusControlOff, - OMX_IMAGE_FocusControlAuto, - OMX_IMAGE_FocusControlAutoLock, - OMX_IMAGE_FocusControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FocusControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FocusControlMax = 0x7FFFFFFF -} OMX_IMAGE_FOCUSCONTROLTYPE; - - -/** - * Focus control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFocusControl : Focus control - * nFocusSteps : Focus can take on values from 0 mm to infinity. - * Interest is only in number of steps over this range. - * nFocusStepIndex : Current focus step index - */ -typedef struct OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FOCUSCONTROLTYPE eFocusControl; - OMX_U32 nFocusSteps; - OMX_U32 nFocusStepIndex; -} OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE; - - -/** - * Q Factor for JPEG compression, which controls the tradeoff between image - * quality and size. Q Factor provides a more simple means of controlling - * JPEG compression quality, without directly programming Quantization - * tables for chroma and luma - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nQFactor : JPEG Q factor value in the range of 1-100. A factor of 1 - * produces the smallest, worst quality images, and a factor - * of 100 produces the largest, best quality images. A - * typical default is 75 for small good quality images - */ -typedef struct OMX_IMAGE_PARAM_QFACTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQFactor; -} OMX_IMAGE_PARAM_QFACTORTYPE; - -/** - * Quantization table type - */ - -typedef enum OMX_IMAGE_QUANTIZATIONTABLETYPE { - OMX_IMAGE_QuantizationTableLuma = 0, - OMX_IMAGE_QuantizationTableChroma, - OMX_IMAGE_QuantizationTableChromaCb, - OMX_IMAGE_QuantizationTableChromaCr, - OMX_IMAGE_QuantizationTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_QuantizationTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_QuantizationTableMax = 0x7FFFFFFF -} OMX_IMAGE_QUANTIZATIONTABLETYPE; - -/** - * JPEG quantization tables are used to determine DCT compression for - * YUV data, as an alternative to specifying Q factor, providing exact - * control of compression - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eQuantizationTable : Quantization table type - * nQuantizationMatrix[64] : JPEG quantization table of coefficients stored - * in increasing columns then by rows of data (i.e. - * row 1, ... row 8). Quantization values are in - * the range 0-255 and stored in linear order - * (i.e. the component will zig-zag the - * quantization table data if required internally) - */ -typedef struct OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_QUANTIZATIONTABLETYPE eQuantizationTable; - OMX_U8 nQuantizationMatrix[64]; -} OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE; - - -/** - * Huffman table type, the same Huffman table is applied for chroma and - * luma component - */ -typedef enum OMX_IMAGE_HUFFMANTABLETYPE { - OMX_IMAGE_HuffmanTableAC = 0, - OMX_IMAGE_HuffmanTableDC, - OMX_IMAGE_HuffmanTableACLuma, - OMX_IMAGE_HuffmanTableACChroma, - OMX_IMAGE_HuffmanTableDCLuma, - OMX_IMAGE_HuffmanTableDCChroma, - OMX_IMAGE_HuffmanTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_HuffmanTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_HuffmanTableMax = 0x7FFFFFFF -} OMX_IMAGE_HUFFMANTABLETYPE; - -/** - * JPEG Huffman table - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eHuffmanTable : Huffman table type - * nNumberOfHuffmanCodeOfLength[16] : 0-16, number of Huffman codes of each - * possible length - * nHuffmanTable[256] : 0-255, the size used for AC and DC - * HuffmanTable are 16 and 162 - */ -typedef struct OMX_IMAGE_PARAM_HUFFMANTTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_HUFFMANTABLETYPE eHuffmanTable; - OMX_U8 nNumberOfHuffmanCodeOfLength[16]; - OMX_U8 nHuffmanTable[256]; -}OMX_IMAGE_PARAM_HUFFMANTTABLETYPE; - -/** @} */ -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Index.h b/third_party/openmax/include/OMX_Index.h deleted file mode 100644 index a1f17487d3..0000000000 --- a/third_party/openmax/include/OMX_Index.h +++ /dev/null @@ -1,259 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Index.h - OpenMax IL version 1.1.2 - * The OMX_Index header file contains the definitions for both applications - * and components . - */ - - -#ifndef OMX_Index_h -#define OMX_Index_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** The OMX_INDEXTYPE enumeration is used to select a structure when either - * getting or setting parameters and/or configuration data. Each entry in - * this enumeration maps to an OMX specified structure. When the - * OMX_GetParameter, OMX_SetParameter, OMX_GetConfig or OMX_SetConfig methods - * are used, the second parameter will always be an entry from this enumeration - * and the third entry will be the structure shown in the comments for the entry. - * For example, if the application is initializing a cropping function, the - * OMX_SetConfig command would have OMX_IndexConfigCommonInputCrop as the second parameter - * and would send a pointer to an initialized OMX_RECTTYPE structure as the - * third parameter. - * - * The enumeration entries named with the OMX_Config prefix are sent using - * the OMX_SetConfig command and the enumeration entries named with the - * OMX_PARAM_ prefix are sent using the OMX_SetParameter command. - */ -typedef enum OMX_INDEXTYPE { - - OMX_IndexComponentStartUnused = 0x01000000, - OMX_IndexParamPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamAudioInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamImageInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamVideoInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamOtherInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamNumAvailableStreams, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamActiveStream, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamSuspensionPolicy, /**< reference: OMX_PARAM_SUSPENSIONPOLICYTYPE */ - OMX_IndexParamComponentSuspended, /**< reference: OMX_PARAM_SUSPENSIONTYPE */ - OMX_IndexConfigCapturing, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigCaptureMode, /**< reference: OMX_CONFIG_CAPTUREMODETYPE */ - OMX_IndexAutoPauseAfterCapture, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexParamContentURI, /**< reference: OMX_PARAM_CONTENTURITYPE */ - OMX_IndexParamCustomContentPipe, /**< reference: OMX_PARAM_CONTENTPIPETYPE */ - OMX_IndexParamDisableResourceConcealment, /**< reference: OMX_RESOURCECONCEALMENTTYPE */ - OMX_IndexConfigMetadataItemCount, /**< reference: OMX_CONFIG_METADATAITEMCOUNTTYPE */ - OMX_IndexConfigContainerNodeCount, /**< reference: OMX_CONFIG_CONTAINERNODECOUNTTYPE */ - OMX_IndexConfigMetadataItem, /**< reference: OMX_CONFIG_METADATAITEMTYPE */ - OMX_IndexConfigCounterNodeID, /**< reference: OMX_CONFIG_CONTAINERNODEIDTYPE */ - OMX_IndexParamMetadataFilterType, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexParamMetadataKeyFilter, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexConfigPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamStandardComponentRole, /**< reference: OMX_PARAM_COMPONENTROLETYPE */ - - OMX_IndexPortStartUnused = 0x02000000, - OMX_IndexParamPortDefinition, /**< reference: OMX_PARAM_PORTDEFINITIONTYPE */ - OMX_IndexParamCompBufferSupplier, /**< reference: OMX_PARAM_BUFFERSUPPLIERTYPE */ - OMX_IndexReservedStartUnused = 0x03000000, - - /* Audio parameters and configurations */ - OMX_IndexAudioStartUnused = 0x04000000, - OMX_IndexParamAudioPortFormat, /**< reference: OMX_AUDIO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamAudioPcm, /**< reference: OMX_AUDIO_PARAM_PCMMODETYPE */ - OMX_IndexParamAudioAac, /**< reference: OMX_AUDIO_PARAM_AACPROFILETYPE */ - OMX_IndexParamAudioRa, /**< reference: OMX_AUDIO_PARAM_RATYPE */ - OMX_IndexParamAudioMp3, /**< reference: OMX_AUDIO_PARAM_MP3TYPE */ - OMX_IndexParamAudioAdpcm, /**< reference: OMX_AUDIO_PARAM_ADPCMTYPE */ - OMX_IndexParamAudioG723, /**< reference: OMX_AUDIO_PARAM_G723TYPE */ - OMX_IndexParamAudioG729, /**< reference: OMX_AUDIO_PARAM_G729TYPE */ - OMX_IndexParamAudioAmr, /**< reference: OMX_AUDIO_PARAM_AMRTYPE */ - OMX_IndexParamAudioWma, /**< reference: OMX_AUDIO_PARAM_WMATYPE */ - OMX_IndexParamAudioSbc, /**< reference: OMX_AUDIO_PARAM_SBCTYPE */ - OMX_IndexParamAudioMidi, /**< reference: OMX_AUDIO_PARAM_MIDITYPE */ - OMX_IndexParamAudioGsm_FR, /**< reference: OMX_AUDIO_PARAM_GSMFRTYPE */ - OMX_IndexParamAudioMidiLoadUserSound, /**< reference: OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE */ - OMX_IndexParamAudioG726, /**< reference: OMX_AUDIO_PARAM_G726TYPE */ - OMX_IndexParamAudioGsm_EFR, /**< reference: OMX_AUDIO_PARAM_GSMEFRTYPE */ - OMX_IndexParamAudioGsm_HR, /**< reference: OMX_AUDIO_PARAM_GSMHRTYPE */ - OMX_IndexParamAudioPdc_FR, /**< reference: OMX_AUDIO_PARAM_PDCFRTYPE */ - OMX_IndexParamAudioPdc_EFR, /**< reference: OMX_AUDIO_PARAM_PDCEFRTYPE */ - OMX_IndexParamAudioPdc_HR, /**< reference: OMX_AUDIO_PARAM_PDCHRTYPE */ - OMX_IndexParamAudioTdma_FR, /**< reference: OMX_AUDIO_PARAM_TDMAFRTYPE */ - OMX_IndexParamAudioTdma_EFR, /**< reference: OMX_AUDIO_PARAM_TDMAEFRTYPE */ - OMX_IndexParamAudioQcelp8, /**< reference: OMX_AUDIO_PARAM_QCELP8TYPE */ - OMX_IndexParamAudioQcelp13, /**< reference: OMX_AUDIO_PARAM_QCELP13TYPE */ - OMX_IndexParamAudioEvrc, /**< reference: OMX_AUDIO_PARAM_EVRCTYPE */ - OMX_IndexParamAudioSmv, /**< reference: OMX_AUDIO_PARAM_SMVTYPE */ - OMX_IndexParamAudioVorbis, /**< reference: OMX_AUDIO_PARAM_VORBISTYPE */ - - OMX_IndexConfigAudioMidiImmediateEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE */ - OMX_IndexConfigAudioMidiControl, /**< reference: OMX_AUDIO_CONFIG_MIDICONTROLTYPE */ - OMX_IndexConfigAudioMidiSoundBankProgram, /**< reference: OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE */ - OMX_IndexConfigAudioMidiStatus, /**< reference: OMX_AUDIO_CONFIG_MIDISTATUSTYPE */ - OMX_IndexConfigAudioMidiMetaEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE */ - OMX_IndexConfigAudioMidiMetaEventData, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE */ - OMX_IndexConfigAudioVolume, /**< reference: OMX_AUDIO_CONFIG_VOLUMETYPE */ - OMX_IndexConfigAudioBalance, /**< reference: OMX_AUDIO_CONFIG_BALANCETYPE */ - OMX_IndexConfigAudioChannelMute, /**< reference: OMX_AUDIO_CONFIG_CHANNELMUTETYPE */ - OMX_IndexConfigAudioMute, /**< reference: OMX_AUDIO_CONFIG_MUTETYPE */ - OMX_IndexConfigAudioLoudness, /**< reference: OMX_AUDIO_CONFIG_LOUDNESSTYPE */ - OMX_IndexConfigAudioEchoCancelation, /**< reference: OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE */ - OMX_IndexConfigAudioNoiseReduction, /**< reference: OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE */ - OMX_IndexConfigAudioBass, /**< reference: OMX_AUDIO_CONFIG_BASSTYPE */ - OMX_IndexConfigAudioTreble, /**< reference: OMX_AUDIO_CONFIG_TREBLETYPE */ - OMX_IndexConfigAudioStereoWidening, /**< reference: OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE */ - OMX_IndexConfigAudioChorus, /**< reference: OMX_AUDIO_CONFIG_CHORUSTYPE */ - OMX_IndexConfigAudioEqualizer, /**< reference: OMX_AUDIO_CONFIG_EQUALIZERTYPE */ - OMX_IndexConfigAudioReverberation, /**< reference: OMX_AUDIO_CONFIG_REVERBERATIONTYPE */ - OMX_IndexConfigAudioChannelVolume, /**< reference: OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE */ - - /* Image specific parameters and configurations */ - OMX_IndexImageStartUnused = 0x05000000, - OMX_IndexParamImagePortFormat, /**< reference: OMX_IMAGE_PARAM_PORTFORMATTYPE */ - OMX_IndexParamFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - OMX_IndexConfigFocusControl, /**< reference: OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE */ - OMX_IndexParamQFactor, /**< reference: OMX_IMAGE_PARAM_QFACTORTYPE */ - OMX_IndexParamQuantizationTable, /**< reference: OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE */ - OMX_IndexParamHuffmanTable, /**< reference: OMX_IMAGE_PARAM_HUFFMANTTABLETYPE */ - OMX_IndexConfigFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - - /* Video specific parameters and configurations */ - OMX_IndexVideoStartUnused = 0x06000000, - OMX_IndexParamVideoPortFormat, /**< reference: OMX_VIDEO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamVideoQuantization, /**< reference: OMX_VIDEO_PARAM_QUANTIZATIONTYPE */ - OMX_IndexParamVideoFastUpdate, /**< reference: OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE */ - OMX_IndexParamVideoBitrate, /**< reference: OMX_VIDEO_PARAM_BITRATETYPE */ - OMX_IndexParamVideoMotionVector, /**< reference: OMX_VIDEO_PARAM_MOTIONVECTORTYPE */ - OMX_IndexParamVideoIntraRefresh, /**< reference: OMX_VIDEO_PARAM_INTRAREFRESHTYPE */ - OMX_IndexParamVideoErrorCorrection, /**< reference: OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE */ - OMX_IndexParamVideoVBSMC, /**< reference: OMX_VIDEO_PARAM_VBSMCTYPE */ - OMX_IndexParamVideoMpeg2, /**< reference: OMX_VIDEO_PARAM_MPEG2TYPE */ - OMX_IndexParamVideoMpeg4, /**< reference: OMX_VIDEO_PARAM_MPEG4TYPE */ - OMX_IndexParamVideoWmv, /**< reference: OMX_VIDEO_PARAM_WMVTYPE */ - OMX_IndexParamVideoRv, /**< reference: OMX_VIDEO_PARAM_RVTYPE */ - OMX_IndexParamVideoAvc, /**< reference: OMX_VIDEO_PARAM_AVCTYPE */ - OMX_IndexParamVideoH263, /**< reference: OMX_VIDEO_PARAM_H263TYPE */ - OMX_IndexParamVideoProfileLevelQuerySupported, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexParamVideoProfileLevelCurrent, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexConfigVideoBitrate, /**< reference: OMX_VIDEO_CONFIG_BITRATETYPE */ - OMX_IndexConfigVideoFramerate, /**< reference: OMX_CONFIG_FRAMERATETYPE */ - OMX_IndexConfigVideoIntraVOPRefresh, /**< reference: OMX_CONFIG_INTRAREFRESHVOPTYPE */ - OMX_IndexConfigVideoIntraMBRefresh, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexConfigVideoMBErrorReporting, /**< reference: OMX_CONFIG_MBERRORREPORTINGTYPE */ - OMX_IndexParamVideoMacroblocksPerFrame, /**< reference: OMX_PARAM_MACROBLOCKSTYPE */ - OMX_IndexConfigVideoMacroBlockErrorMap, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexParamVideoSliceFMO, /**< reference: OMX_VIDEO_PARAM_AVCSLICEFMO */ - OMX_IndexConfigVideoAVCIntraPeriod, /**< reference: OMX_VIDEO_CONFIG_AVCINTRAPERIOD */ - OMX_IndexConfigVideoNalSize, /**< reference: OMX_VIDEO_CONFIG_NALSIZE */ - OMX_IndexConfigCommonDeinterlace, /**< reference: OMX_VIDEO_CONFIG_DEINTERLACE */ - - /* Image & Video common Configurations */ - OMX_IndexCommonStartUnused = 0x07000000, - OMX_IndexParamCommonDeblocking, /**< reference: OMX_PARAM_DEBLOCKINGTYPE */ - OMX_IndexParamCommonSensorMode, /**< reference: OMX_PARAM_SENSORMODETYPE */ - OMX_IndexParamCommonInterleave, /**< reference: OMX_PARAM_INTERLEAVETYPE */ - OMX_IndexConfigCommonColorFormatConversion, /**< reference: OMX_CONFIG_COLORCONVERSIONTYPE */ - OMX_IndexConfigCommonScale, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonImageFilter, /**< reference: OMX_CONFIG_IMAGEFILTERTYPE */ - OMX_IndexConfigCommonColorEnhancement, /**< reference: OMX_CONFIG_COLORENHANCEMENTTYPE */ - OMX_IndexConfigCommonColorKey, /**< reference: OMX_CONFIG_COLORKEYTYPE */ - OMX_IndexConfigCommonColorBlend, /**< reference: OMX_CONFIG_COLORBLENDTYPE */ - OMX_IndexConfigCommonFrameStabilisation,/**< reference: OMX_CONFIG_FRAMESTABTYPE */ - OMX_IndexConfigCommonRotate, /**< reference: OMX_CONFIG_ROTATIONTYPE */ - OMX_IndexConfigCommonMirror, /**< reference: OMX_CONFIG_MIRRORTYPE */ - OMX_IndexConfigCommonOutputPosition, /**< reference: OMX_CONFIG_POINTTYPE */ - OMX_IndexConfigCommonInputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonOutputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDigitalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonOpticalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE*/ - OMX_IndexConfigCommonWhiteBalance, /**< reference: OMX_CONFIG_WHITEBALCONTROLTYPE */ - OMX_IndexConfigCommonExposure, /**< reference: OMX_CONFIG_EXPOSURECONTROLTYPE */ - OMX_IndexConfigCommonContrast, /**< reference: OMX_CONFIG_CONTRASTTYPE */ - OMX_IndexConfigCommonBrightness, /**< reference: OMX_CONFIG_BRIGHTNESSTYPE */ - OMX_IndexConfigCommonBacklight, /**< reference: OMX_CONFIG_BACKLIGHTTYPE */ - OMX_IndexConfigCommonGamma, /**< reference: OMX_CONFIG_GAMMATYPE */ - OMX_IndexConfigCommonSaturation, /**< reference: OMX_CONFIG_SATURATIONTYPE */ - OMX_IndexConfigCommonLightness, /**< reference: OMX_CONFIG_LIGHTNESSTYPE */ - OMX_IndexConfigCommonExclusionRect, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDithering, /**< reference: OMX_CONFIG_DITHERTYPE */ - OMX_IndexConfigCommonPlaneBlend, /**< reference: OMX_CONFIG_PLANEBLENDTYPE */ - OMX_IndexConfigCommonExposureValue, /**< reference: OMX_CONFIG_EXPOSUREVALUETYPE */ - OMX_IndexConfigCommonOutputSize, /**< reference: OMX_FRAMESIZETYPE */ - OMX_IndexParamCommonExtraQuantData, /**< reference: OMX_OTHER_EXTRADATATYPE */ - OMX_IndexConfigCommonFocusRegion, /**< reference: OMX_CONFIG_FOCUSREGIONTYPE */ - OMX_IndexConfigCommonFocusStatus, /**< reference: OMX_PARAM_FOCUSSTATUSTYPE */ - OMX_IndexConfigCommonTransitionEffect, /**< reference: OMX_CONFIG_TRANSITIONEFFECTTYPE */ - - /* Reserved Configuration range */ - OMX_IndexOtherStartUnused = 0x08000000, - OMX_IndexParamOtherPortFormat, /**< reference: OMX_OTHER_PARAM_PORTFORMATTYPE */ - OMX_IndexConfigOtherPower, /**< reference: OMX_OTHER_CONFIG_POWERTYPE */ - OMX_IndexConfigOtherStats, /**< reference: OMX_OTHER_CONFIG_STATSTYPE */ - - - /* Reserved Time range */ - OMX_IndexTimeStartUnused = 0x09000000, - OMX_IndexConfigTimeScale, /**< reference: OMX_TIME_CONFIG_SCALETYPE */ - OMX_IndexConfigTimeClockState, /**< reference: OMX_TIME_CONFIG_CLOCKSTATETYPE */ - OMX_IndexConfigTimeActiveRefClock, /**< reference: OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE */ - OMX_IndexConfigTimeCurrentMediaTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentWallTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentAudioReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeCurrentVideoReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeMediaTimeRequest, /**< reference: OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE (write only) */ - OMX_IndexConfigTimeClientStartTime, /** - - -/** Khronos standard extension indices. - -This enum lists the current Khronos extension indices to OpenMAX IL. -*/ -typedef enum OMX_INDEXEXTTYPE { - - /* Component parameters and configurations */ - OMX_IndexExtComponentStartUnused = OMX_IndexKhronosExtensions + 0x00100000, - OMX_IndexConfigCallbackRequest, /**< reference: OMX_CONFIG_CALLBACKREQUESTTYPE */ - OMX_IndexConfigCommitMode, /**< reference: OMX_CONFIG_COMMITMODETYPE */ - OMX_IndexConfigCommit, /**< reference: OMX_CONFIG_COMMITTYPE */ - - /* Port parameters and configurations */ - OMX_IndexExtPortStartUnused = OMX_IndexKhronosExtensions + 0x00200000, - - /* Audio parameters and configurations */ - OMX_IndexExtAudioStartUnused = OMX_IndexKhronosExtensions + 0x00400000, - - /* Image parameters and configurations */ - OMX_IndexExtImageStartUnused = OMX_IndexKhronosExtensions + 0x00500000, - - /* Video parameters and configurations */ - OMX_IndexExtVideoStartUnused = OMX_IndexKhronosExtensions + 0x00600000, - OMX_IndexParamNalStreamFormatSupported, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormat, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormatSelect, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamVideoVp8, /**< reference: OMX_VIDEO_PARAM_VP8TYPE */ - OMX_IndexConfigVideoVp8ReferenceFrame, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMETYPE */ - OMX_IndexConfigVideoVp8ReferenceFrameType, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE */ - OMX_IndexParamVideoReserved, /**< Reserved for future index */ - OMX_IndexParamVideoHevc, /**< reference: OMX_VIDEO_PARAM_HEVCTYPE */ - - /* Image & Video common configurations */ - OMX_IndexExtCommonStartUnused = OMX_IndexKhronosExtensions + 0x00700000, - - /* Other configurations */ - OMX_IndexExtOtherStartUnused = OMX_IndexKhronosExtensions + 0x00800000, - OMX_IndexConfigAutoFramerateConversion, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigPriority, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexConfigOperatingRate, /**< reference: OMX_PARAM_U32TYPE in Q16 format for video and in Hz for audio */ - - /* Time configurations */ - OMX_IndexExtTimeStartUnused = OMX_IndexKhronosExtensions + 0x00900000, - - OMX_IndexExtMax = 0x7FFFFFFF -} OMX_INDEXEXTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_IndexExt_h */ -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Other.h b/third_party/openmax/include/OMX_Other.h deleted file mode 100644 index caf7f38448..0000000000 --- a/third_party/openmax/include/OMX_Other.h +++ /dev/null @@ -1,337 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Other.h - OpenMax IL version 1.1.2 - * The structures needed by Other components to exchange - * parameters and configuration data with the components. - */ - -#ifndef OMX_Other_h -#define OMX_Other_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration of possible data types which match to multiple domains or no - * domain at all. For types which are vendor specific, a value above - * OMX_OTHER_VENDORTSTART should be used. - */ -typedef enum OMX_OTHER_FORMATTYPE { - OMX_OTHER_FormatTime = 0, /**< Transmission of various timestamps, elapsed time, - time deltas, etc */ - OMX_OTHER_FormatPower, /**< Perhaps used for enabling/disabling power - management, setting clocks? */ - OMX_OTHER_FormatStats, /**< Could be things such as frame rate, frames - dropped, etc */ - OMX_OTHER_FormatBinary, /**< Arbitrary binary data */ - OMX_OTHER_FormatVendorReserved = 1000, /**< Starting value for vendor specific - formats */ - - OMX_OTHER_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_OTHER_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_OTHER_FormatMax = 0x7FFFFFFF -} OMX_OTHER_FORMATTYPE; - -/** - * Enumeration of seek modes. - */ -typedef enum OMX_TIME_SEEKMODETYPE { - OMX_TIME_SeekModeFast = 0, /**< Prefer seeking to an approximation - * of the requested seek position over - * the actual seek position if it - * results in a faster seek. */ - OMX_TIME_SeekModeAccurate, /**< Prefer seeking to the actual seek - * position over an approximation - * of the requested seek position even - * if it results in a slower seek. */ - OMX_TIME_SeekModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_SeekModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_SeekModeMax = 0x7FFFFFFF -} OMX_TIME_SEEKMODETYPE; - -/* Structure representing the seekmode of the component */ -typedef struct OMX_TIME_CONFIG_SEEKMODETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_SEEKMODETYPE eType; /**< The seek mode */ -} OMX_TIME_CONFIG_SEEKMODETYPE; - -/** Structure representing a time stamp used with the following configs - * on the Clock Component (CC): - * - * OMX_IndexConfigTimeCurrentWallTime: query of the CC’s current wall - * time - * OMX_IndexConfigTimeCurrentMediaTime: query of the CC’s current media - * time - * OMX_IndexConfigTimeCurrentAudioReference and - * OMX_IndexConfigTimeCurrentVideoReference: audio/video reference - * clock sending SC its reference time - * OMX_IndexConfigTimeClientStartTime: a Clock Component client sends - * this structure to the Clock Component via a SetConfig on its - * client port when it receives a buffer with - * OMX_BUFFERFLAG_STARTTIME set. It must use the timestamp - * specified by that buffer for nStartTimestamp. - * - * It’s also used with the following config on components in general: - * - * OMX_IndexConfigTimePosition: IL client querying component position - * (GetConfig) or commanding a component to seek to the given location - * (SetConfig) - */ -typedef struct OMX_TIME_CONFIG_TIMESTAMPTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_TICKS nTimestamp; /**< timestamp .*/ -} OMX_TIME_CONFIG_TIMESTAMPTYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_UPDATETYPE { - OMX_TIME_UpdateRequestFulfillment, /**< Update is the fulfillment of a media time request. */ - OMX_TIME_UpdateScaleChanged, /**< Update was generated because the scale chagned. */ - OMX_TIME_UpdateClockStateChanged, /**< Update was generated because the clock state changed. */ - OMX_TIME_UpdateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_UpdateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_UpdateMax = 0x7FFFFFFF -} OMX_TIME_UPDATETYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_REFCLOCKTYPE { - OMX_TIME_RefClockNone, /**< Use no references. */ - OMX_TIME_RefClockAudio, /**< Use references sent through OMX_IndexConfigTimeCurrentAudioReference */ - OMX_TIME_RefClockVideo, /**< Use references sent through OMX_IndexConfigTimeCurrentVideoReference */ - OMX_TIME_RefClockKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_RefClockVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_RefClockMax = 0x7FFFFFFF -} OMX_TIME_REFCLOCKTYPE; - -/** Enumeration of clock states. */ -typedef enum OMX_TIME_CLOCKSTATE { - OMX_TIME_ClockStateRunning, /**< Clock running. */ - OMX_TIME_ClockStateWaitingForStartTime, /**< Clock waiting until the - * prescribed clients emit their - * start time. */ - OMX_TIME_ClockStateStopped, /**< Clock stopped. */ - OMX_TIME_ClockStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_ClockStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_ClockStateMax = 0x7FFFFFFF -} OMX_TIME_CLOCKSTATE; - -/** Structure representing a media time request to the clock component. - * - * A client component sends this structure to the Clock Component via a SetConfig - * on its client port to specify a media timestamp the Clock Component - * should emit. The Clock Component should fulfill the request by sending a - * OMX_TIME_MEDIATIMETYPE when its media clock matches the requested - * timestamp. - * - * The client may require a media time request be fulfilled slightly - * earlier than the media time specified. In this case the client specifies - * an offset which is equal to the difference between wall time corresponding - * to the requested media time and the wall time when it will be - * fulfilled. - * - * A client component may uses these requests and the OMX_TIME_MEDIATIMETYPE to - * time events according to timestamps. If a client must perform an operation O at - * a time T (e.g. deliver a video frame at its corresponding timestamp), it makes a - * media time request at T (perhaps specifying an offset to ensure the request fulfillment - * is a little early). When the clock component passes the resulting OMX_TIME_MEDIATIMETYPE - * structure back to the client component, the client may perform operation O (perhaps having - * to wait a slight amount more time itself as specified by the return values). - */ - -typedef struct OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_PTR pClientPrivate; /**< Client private data to disabiguate this media time - * from others (e.g. the number of the frame to deliver). - * Duplicated in the media time structure that fulfills - * this request. A value of zero is reserved for time scale - * updates. */ - OMX_TICKS nMediaTimestamp; /**< Media timestamp requested.*/ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request should be fulfilled early */ -} OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE; - -/**< Structure sent from the clock component client either when fulfilling - * a media time request or when the time scale has changed. - * - * In the former case the Clock Component fills this structure and times its emission - * to a client component (via the client port) according to the corresponding media - * time request sent by the client. The Clock Component should time the emission to occur - * when the requested timestamp matches the Clock Component's media time but also the - * prescribed offset early. - * - * Upon scale changes the clock component clears the nClientPrivate data, sends the current - * media time and sets the nScale to the new scale via the client port. It emits a - * OMX_TIME_MEDIATIMETYPE to all clients independent of any requests. This allows clients to - * alter processing to accomodate scaling. For instance a video component might skip inter-frames - * in the case of extreme fastforward. Likewise an audio component might add or remove samples - * from an audio frame to scale audio data. - * - * It is expected that some clock components may not be able to fulfill requests - * at exactly the prescribed time. This is acceptable so long as the request is - * fulfilled at least as early as described and not later. This structure provides - * fields the client may use to wait for the remaining time. - * - * The client may use either the nOffset or nWallTimeAtMedia fields to determine the - * wall time until the nMediaTimestamp actually occurs. In the latter case the - * client can get a more accurate value for offset by getting the current wall - * from the cloc component and subtracting it from nWallTimeAtMedia. - */ - -typedef struct OMX_TIME_MEDIATIMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nClientPrivate; /**< Client private data to disabiguate this media time - * from others. Copied from the media time request. - * A value of zero is reserved for time scale updates. */ - OMX_TIME_UPDATETYPE eUpdateType; /**< Reason for the update */ - OMX_TICKS nMediaTimestamp; /**< Media time requested. If no media time was - * requested then this is the current media time. */ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request was actually fulfilled early */ - - OMX_TICKS nWallTimeAtMediaTime; /**< Wall time corresponding to nMediaTimeStamp. - * A client may compare this value to current - * media time obtained from the Clock Component to determine - * the wall time until the media timestamp is really - * current. */ - OMX_S32 xScale; /**< Current media time scale in Q16 format. */ - OMX_TIME_CLOCKSTATE eState; /* Seeking Change. Added 7/12.*/ - /**< State of the media time. */ -} OMX_TIME_MEDIATIMETYPE; - -/** Structure representing the current media time scale factor. Applicable only to clock - * component, other components see scale changes via OMX_TIME_MEDIATIMETYPE buffers sent via - * the clock component client ports. Upon recieving this config the clock component changes - * the rate by which the media time increases or decreases effectively implementing trick modes. - */ -typedef struct OMX_TIME_CONFIG_SCALETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_S32 xScale; /**< This is a value in Q16 format which is used for - * scaling the media time */ -} OMX_TIME_CONFIG_SCALETYPE; - -/** Bits used to identify a clock port. Used in OMX_TIME_CONFIG_CLOCKSTATETYPE’s nWaitMask field */ -#define OMX_CLOCKPORT0 0x00000001 -#define OMX_CLOCKPORT1 0x00000002 -#define OMX_CLOCKPORT2 0x00000004 -#define OMX_CLOCKPORT3 0x00000008 -#define OMX_CLOCKPORT4 0x00000010 -#define OMX_CLOCKPORT5 0x00000020 -#define OMX_CLOCKPORT6 0x00000040 -#define OMX_CLOCKPORT7 0x00000080 - -/** Structure representing the current mode of the media clock. - * IL Client uses this config to change or query the mode of the - * media clock of the clock component. Applicable only to clock - * component. - * - * On a SetConfig if eState is OMX_TIME_ClockStateRunning media time - * starts immediately at the prescribed start time. If - * OMX_TIME_ClockStateWaitingForStartTime the Clock Component ignores - * the given nStartTime and waits for all clients specified in the - * nWaitMask to send starttimes (via - * OMX_IndexConfigTimeClientStartTime). The Clock Component then starts - * the media clock using the earliest start time supplied. */ -typedef struct OMX_TIME_CONFIG_CLOCKSTATETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_TIME_CLOCKSTATE eState; /**< State of the media time. */ - OMX_TICKS nStartTime; /**< Start time of the media time. */ - OMX_TICKS nOffset; /**< Time to offset the media time by - * (e.g. preroll). Media time will be - * reported to be nOffset ticks earlier. - */ - OMX_U32 nWaitMask; /**< Mask of OMX_CLOCKPORT values. */ -} OMX_TIME_CONFIG_CLOCKSTATETYPE; - -/** Structure representing the reference clock currently being used to - * compute media time. IL client uses this config to change or query the - * clock component's active reference clock */ -typedef struct OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_REFCLOCKTYPE eClock; /**< Reference clock used to compute media time */ -} OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE; - -/** Descriptor for setting specifics of power type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_POWERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bEnablePM; /**< Flag to enable Power Management */ -} OMX_OTHER_CONFIG_POWERTYPE; - - -/** Descriptor for setting specifics of stats type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_STATSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - /* what goes here */ -} OMX_OTHER_CONFIG_STATSTYPE; - - -/** - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output other - * path. - */ -typedef struct OMX_OTHER_PORTDEFINITIONTYPE { - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PORTDEFINITIONTYPE; - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_OTHER_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PARAM_PORTFORMATTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_QCOMExtns.h b/third_party/openmax/include/OMX_QCOMExtns.h deleted file mode 100644 index 20917932be..0000000000 --- a/third_party/openmax/include/OMX_QCOMExtns.h +++ /dev/null @@ -1,1888 +0,0 @@ -/*-------------------------------------------------------------------------- -Copyright (c) 2009-2015, The Linux Foundation. All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Neither the name of The Linux Foundation nor - the names of its contributors may be used to endorse or promote - products derived from this software without specific prior written - permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND -NON-INFRINGEMENT ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR -CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, -EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ---------------------------------------------------------------------------*/ -#ifndef __OMX_QCOM_EXTENSIONS_H__ -#define __OMX_QCOM_EXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/*============================================================================ -*//** @file OMX_QCOMExtns.h - This header contains constants and type definitions that specify the - extensions added to the OpenMAX Vendor specific APIs. - -*//*========================================================================*/ - - -/////////////////////////////////////////////////////////////////////////////// -// Include Files -/////////////////////////////////////////////////////////////////////////////// -#include "OMX_Core.h" -#include "OMX_Video.h" - -#define OMX_VIDEO_MAX_HP_LAYERS 6 -/** - * This extension is used to register mapping of a virtual - * address to a physical address. This extension is a parameter - * which can be set using the OMX_SetParameter macro. The data - * pointer corresponding to this extension is - * OMX_QCOM_MemMapEntry. This parameter is a 'write only' - * parameter (Current value cannot be queried using - * OMX_GetParameter macro). - */ -#define OMX_QCOM_EXTN_REGISTER_MMAP "OMX.QCOM.index.param.register_mmap" - -/** - * This structure describes the data pointer corresponding to - * the OMX_QCOM_MMAP_REGISTER_EXTN extension. This parameter - * must be set only 'after' populating a port with a buffer - * using OMX_UseBuffer, wherein the data pointer of the buffer - * corresponds to the virtual address as specified in this - * structure. - */ -struct OMX_QCOM_PARAM_MEMMAPENTRYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - - /** - * The virtual address of memory block - */ - OMX_U64 nVirtualAddress; - - /** - * The physical address corresponding to the virtual address. The physical - * address is contiguous for the entire valid range of the virtual - * address. - */ - OMX_U64 nPhysicalAddress; -}; - -#define QOMX_VIDEO_IntraRefreshRandom (OMX_VIDEO_IntraRefreshVendorStartUnused + 0) - -/* This error event is used for H.264 long-term reference (LTR) encoding. - * When IL client specifies an LTR frame with its identifier via - * OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE to the encoder, if the specified - * LTR frame can not be located by the encoder in its LTR list, the encoder - * issues this error event to IL client to notify the failure of LTRUse config. - */ -#define QOMX_ErrorLTRUseFailed (OMX_ErrorVendorStartUnused + 1) - -#define QOMX_VIDEO_BUFFERFLAG_BFRAME 0x00100000 - -#define QOMX_VIDEO_BUFFERFLAG_EOSEQ 0x00200000 - -#define QOMX_VIDEO_BUFFERFLAG_MBAFF 0x00400000 - -#define QOMX_VIDEO_BUFFERFLAG_CANCEL 0x00800000 - -#define OMX_QCOM_PORTDEFN_EXTN "OMX.QCOM.index.param.portdefn" -/* Allowed APIs on the above Index: OMX_GetParameter() and OMX_SetParameter() */ - -typedef enum OMX_QCOMMemoryRegion -{ - OMX_QCOM_MemRegionInvalid, - OMX_QCOM_MemRegionEBI1, - OMX_QCOM_MemRegionSMI, - OMX_QCOM_MemRegionMax = 0X7FFFFFFF -} OMX_QCOMMemoryRegion; - -typedef enum OMX_QCOMCacheAttr -{ - OMX_QCOM_CacheAttrNone, - OMX_QCOM_CacheAttrWriteBack, - OMX_QCOM_CacheAttrWriteThrough, - OMX_QCOM_CacheAttrMAX = 0X7FFFFFFF -} OMX_QCOMCacheAttr; - -typedef struct OMX_QCOMRectangle -{ - OMX_S32 x; - OMX_S32 y; - OMX_S32 dx; - OMX_S32 dy; -} OMX_QCOMRectangle; - -/** OMX_QCOMFramePackingFormat - * Input or output buffer format - */ -typedef enum OMX_QCOMFramePackingFormat -{ - /* 0 - unspecified - */ - OMX_QCOM_FramePacking_Unspecified, - - /* 1 - Partial frames may be present OMX IL 1.1.1 Figure 2-10: - * Case 1??Each Buffer Filled In Whole or In Part - */ - OMX_QCOM_FramePacking_Arbitrary, - - /* 2 - Multiple complete frames per buffer (integer number) - * OMX IL 1.1.1 Figure 2-11: Case 2—Each Buffer Filled with - * Only Complete Frames of Data - */ - OMX_QCOM_FramePacking_CompleteFrames, - - /* 3 - Only one complete frame per buffer, no partial frame - * OMX IL 1.1.1 Figure 2-12: Case 3—Each Buffer Filled with - * Only One Frame of Compressed Data. Usually at least one - * complete unit of data will be delivered in a buffer for - * uncompressed data formats. - */ - OMX_QCOM_FramePacking_OnlyOneCompleteFrame, - - /* 4 - Only one complete subframe per buffer, no partial subframe - * Example: In H264, one complete NAL per buffer, where one frame - * can contatin multiple NAL - */ - OMX_QCOM_FramePacking_OnlyOneCompleteSubFrame, - - OMX_QCOM_FramePacking_MAX = 0X7FFFFFFF -} OMX_QCOMFramePackingFormat; - -typedef struct OMX_QCOM_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - - /** Platform specific memory region EBI1, SMI, etc.,*/ - OMX_QCOMMemoryRegion nMemRegion; - - OMX_QCOMCacheAttr nCacheAttr; /** Cache attributes */ - - /** Input or output buffer format */ - OMX_U32 nFramePackingFormat; - -} OMX_QCOM_PARAM_PORTDEFINITIONTYPE; - -typedef struct OMX_QCOM_VIDEO_PARAM_QPRANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 minQP; - OMX_U32 maxQP; -} OMX_QCOM_VIDEO_PARAM_QPRANGETYPE; - -#define OMX_QCOM_PLATFORMPVT_EXTN "OMX.QCOM.index.param.platformprivate" -/** Allowed APIs on the above Index: OMX_SetParameter() */ - -typedef enum OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE -{ - /** Enum for PMEM information */ - OMX_QCOM_PLATFORM_PRIVATE_PMEM = 0x1 -} OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE; - -/** IL client will set the following structure. A failure - * code will be returned if component does not support the - * value provided for 'type'. - */ -struct OMX_QCOM_PLATFORMPRIVATE_EXTN -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX spec version information */ - OMX_U32 nPortIndex; /** Port number on which usebuffer extn is applied */ - - /** Type of extensions should match an entry from - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; -}; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO -{ - /** pmem file descriptor */ - unsigned long pmem_fd; - /** Offset from pmem device base address */ - OMX_U32 offset; - OMX_U32 size; - OMX_U32 mapped_size; - OMX_PTR buffer; -}OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_ENTRY -{ - /** Entry type */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; - - /** Pointer to platform specific entry */ - OMX_PTR entry; -}OMX_QCOM_PLATFORM_PRIVATE_ENTRY; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_LIST -{ - /** Number of entries */ - OMX_U32 nEntries; - - /** Pointer to array of platform specific entries * - * Contiguous block of OMX_QCOM_PLATFORM_PRIVATE_ENTRY element - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY* entryList; -}OMX_QCOM_PLATFORM_PRIVATE_LIST; - -#define OMX_QCOM_FRAME_PACKING_FORMAT "OMX.QCOM.index.param.framepackfmt" -/* Allowed API call: OMX_GetParameter() */ -/* IL client can use this index to rerieve the list of frame formats * - * supported by the component */ - -typedef struct OMX_QCOM_FRAME_PACKINGFORMAT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOMFramePackingFormat eframePackingFormat; -} OMX_QCOM_FRAME_PACKINGFORMAT_TYPE; - - -/** - * Following is the enum for color formats supported on Qualcomm - * MSMs YVU420SemiPlanar color format is not defined in OpenMAX - * 1.1.1 and prior versions of OpenMAX specification. - */ - -enum OMX_QCOM_COLOR_FORMATTYPE -{ - -/** YVU420SemiPlanar: YVU planar format, organized with a first - * plane containing Y pixels, and a second plane containing - * interleaved V and U pixels. V and U pixels are sub-sampled - * by a factor of two both horizontally and vertically. - */ - QOMX_COLOR_FormatYVU420SemiPlanar = 0x7FA30C00, - QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed, - QOMX_COLOR_Format32bitRGBA8888, - QOMX_COLOR_Format32bitRGBA8888Compressed, - QOMX_COLOR_FormatAndroidOpaque = (OMX_COLOR_FORMATTYPE) OMX_COLOR_FormatVendorStartUnused + 0x789, -}; - -enum OMX_QCOM_VIDEO_CODINGTYPE -{ -/** Codecs support by qualcomm which are not listed in OMX 1.1.x - * spec - * */ - OMX_QCOM_VIDEO_CodingVC1 = 0x7FA30C00 , - OMX_QCOM_VIDEO_CodingWMV9 = 0x7FA30C01, - QOMX_VIDEO_CodingDivx = 0x7FA30C02, /**< Value when coding is Divx */ - QOMX_VIDEO_CodingSpark = 0x7FA30C03, /**< Value when coding is Sorenson Spark */ - QOMX_VIDEO_CodingVp = 0x7FA30C04, - QOMX_VIDEO_CodingVp8 = OMX_VIDEO_CodingVP8, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingHevc = OMX_VIDEO_CodingHEVC, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingMVC = 0x7FA30C07, - QOMX_VIDEO_CodingVp9 = OMX_VIDEO_CodingVP9, /**< keeping old enum for backwards compatibility*/ -}; - -enum OMX_QCOM_EXTN_INDEXTYPE -{ - /** Qcom proprietary extension index list */ - - /* "OMX.QCOM.index.param.register_mmap" */ - OMX_QcomIndexRegmmap = 0x7F000000, - - /* "OMX.QCOM.index.param.platformprivate" */ - OMX_QcomIndexPlatformPvt = 0x7F000001, - - /* "OMX.QCOM.index.param.portdefn" */ - OMX_QcomIndexPortDefn = 0x7F000002, - - /* "OMX.QCOM.index.param.framepackingformat" */ - OMX_QcomIndexPortFramePackFmt = 0x7F000003, - - /*"OMX.QCOM.index.param.Interlaced */ - OMX_QcomIndexParamInterlaced = 0x7F000004, - - /*"OMX.QCOM.index.config.interlaceformat */ - OMX_QcomIndexConfigInterlaced = 0x7F000005, - - /*"OMX.QCOM.index.param.syntaxhdr" */ - QOMX_IndexParamVideoSyntaxHdr = 0x7F000006, - - /*"OMX.QCOM.index.config.intraperiod" */ - QOMX_IndexConfigVideoIntraperiod = 0x7F000007, - - /*"OMX.QCOM.index.config.randomIntrarefresh" */ - QOMX_IndexConfigVideoIntraRefresh = 0x7F000008, - - /*"OMX.QCOM.index.config.video.TemporalSpatialTradeOff" */ - QOMX_IndexConfigVideoTemporalSpatialTradeOff = 0x7F000009, - - /*"OMX.QCOM.index.param.video.EncoderMode" */ - QOMX_IndexParamVideoEncoderMode = 0x7F00000A, - - /*"OMX.QCOM.index.param.Divxtype */ - OMX_QcomIndexParamVideoDivx = 0x7F00000B, - - /*"OMX.QCOM.index.param.Sparktype */ - OMX_QcomIndexParamVideoSpark = 0x7F00000C, - - /*"OMX.QCOM.index.param.Vptype */ - OMX_QcomIndexParamVideoVp = 0x7F00000D, - - OMX_QcomIndexQueryNumberOfVideoDecInstance = 0x7F00000E, - - OMX_QcomIndexParamVideoSyncFrameDecodingMode = 0x7F00000F, - - OMX_QcomIndexParamVideoDecoderPictureOrder = 0x7F000010, - - /* "OMX.QCOM.index.config.video.FramePackingInfo" */ - OMX_QcomIndexConfigVideoFramePackingArrangement = 0x7F000011, - - OMX_QcomIndexParamConcealMBMapExtraData = 0x7F000012, - - OMX_QcomIndexParamFrameInfoExtraData = 0x7F000013, - - OMX_QcomIndexParamInterlaceExtraData = 0x7F000014, - - OMX_QcomIndexParamH264TimeInfo = 0x7F000015, - - OMX_QcomIndexParamIndexExtraDataType = 0x7F000016, - - OMX_GoogleAndroidIndexEnableAndroidNativeBuffers = 0x7F000017, - - OMX_GoogleAndroidIndexUseAndroidNativeBuffer = 0x7F000018, - - OMX_GoogleAndroidIndexGetAndroidNativeBufferUsage = 0x7F000019, - - /*"OMX.QCOM.index.config.video.QPRange" */ - OMX_QcomIndexConfigVideoQPRange = 0x7F00001A, - - /*"OMX.QCOM.index.param.EnableTimeStampReoder"*/ - OMX_QcomIndexParamEnableTimeStampReorder = 0x7F00001B, - - /*"OMX.google.android.index.storeMetaDataInBuffers"*/ - OMX_QcomIndexParamVideoMetaBufferMode = 0x7F00001C, - - /*"OMX.google.android.index.useAndroidNativeBuffer2"*/ - OMX_GoogleAndroidIndexUseAndroidNativeBuffer2 = 0x7F00001D, - - /*"OMX.QCOM.index.param.VideoMaxAllowedBitrateCheck"*/ - OMX_QcomIndexParamVideoMaxAllowedBitrateCheck = 0x7F00001E, - - OMX_QcomIndexEnableSliceDeliveryMode = 0x7F00001F, - - /* "OMX.QCOM.index.param.video.ExtnUserExtraData" */ - OMX_QcomIndexEnableExtnUserData = 0x7F000020, - - /*"OMX.QCOM.index.param.video.EnableSmoothStreaming"*/ - OMX_QcomIndexParamEnableSmoothStreaming = 0x7F000021, - - /*"OMX.QCOM.index.param.video.QPRange" */ - OMX_QcomIndexParamVideoQPRange = 0x7F000022, - - OMX_QcomIndexEnableH263PlusPType = 0x7F000023, - - /*"OMX.QCOM.index.param.video.LTRCountRangeSupported"*/ - QOMX_IndexParamVideoLTRCountRangeSupported = 0x7F000024, - - /*"OMX.QCOM.index.param.video.LTRMode"*/ - QOMX_IndexParamVideoLTRMode = 0x7F000025, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - QOMX_IndexParamVideoLTRCount = 0x7F000026, - - /*"OMX.QCOM.index.config.video.LTRPeriod"*/ - QOMX_IndexConfigVideoLTRPeriod = 0x7F000027, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - QOMX_IndexConfigVideoLTRUse = 0x7F000028, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - QOMX_IndexConfigVideoLTRMark = 0x7F000029, - - /* OMX.google.android.index.prependSPSPPSToIDRFrames */ - OMX_QcomIndexParamSequenceHeaderWithIDR = 0x7F00002A, - - OMX_QcomIndexParamH264AUDelimiter = 0x7F00002B, - - OMX_QcomIndexParamVideoDownScalar = 0x7F00002C, - - /* "OMX.QCOM.index.param.video.FramePackingExtradata" */ - OMX_QcomIndexParamVideoFramePackingExtradata = 0x7F00002D, - - /* "OMX.QCOM.index.config.activeregiondetection" */ - OMX_QcomIndexConfigActiveRegionDetection = 0x7F00002E, - - /* "OMX.QCOM.index.config.activeregiondetectionstatus" */ - OMX_QcomIndexConfigActiveRegionDetectionStatus = 0x7F00002F, - - /* "OMX.QCOM.index.config.scalingmode" */ - OMX_QcomIndexConfigScalingMode = 0x7F000030, - - /* "OMX.QCOM.index.config.noisereduction" */ - OMX_QcomIndexConfigNoiseReduction = 0x7F000031, - - /* "OMX.QCOM.index.config.imageenhancement" */ - OMX_QcomIndexConfigImageEnhancement = 0x7F000032, - - /* google smooth-streaming support */ - OMX_QcomIndexParamVideoAdaptivePlaybackMode = 0x7F000033, - - /* H.264 MVC codec index */ - QOMX_IndexParamVideoMvc = 0x7F000034, - - /* "OMX.QCOM.index.param.video.QPExtradata" */ - OMX_QcomIndexParamVideoQPExtraData = 0x7F000035, - - /* "OMX.QCOM.index.param.video.InputBitsInfoExtradata" */ - OMX_QcomIndexParamVideoInputBitsInfoExtraData = 0x7F000036, - - /* VP8 Hierarchical P support */ - OMX_QcomIndexHierarchicalStructure = 0x7F000037, - - OMX_QcomIndexParamPerfLevel = 0x7F000038, - - OMX_QcomIndexParamH264VUITimingInfo = 0x7F000039, - - OMX_QcomIndexParamPeakBitrate = 0x7F00003A, - - /* Enable InitialQP index */ - QOMX_IndexParamVideoInitialQp = 0x7F00003B, - - OMX_QcomIndexParamSetMVSearchrange = 0x7F00003C, - - OMX_QcomIndexConfigPerfLevel = 0x7F00003D, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - OMX_QcomIndexParamVideoLTRCount = QOMX_IndexParamVideoLTRCount, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - OMX_QcomIndexConfigVideoLTRUse = QOMX_IndexConfigVideoLTRUse, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - OMX_QcomIndexConfigVideoLTRMark = QOMX_IndexConfigVideoLTRMark, - - /*"OMX.QCOM.index.param.video.CustomBufferSize"*/ - OMX_QcomIndexParamVideoCustomBufferSize = 0x7F00003E, - - /* Max Hierarchical P layers */ - OMX_QcomIndexMaxHierarchicallayers = 0x7F000041, - - /* Set Encoder Performance Index */ - OMX_QcomIndexConfigVideoVencPerfMode = 0x7F000042, - - /* Set Hybrid Hier-p layers */ - OMX_QcomIndexParamVideoHybridHierpMode = 0x7F000043, - - OMX_QcomIndexFlexibleYUVDescription = 0x7F000044, - - /* Vpp Hqv Control Type */ - OMX_QcomIndexParamVppHqvControl = 0x7F000045, - - /* Enable VPP */ - OMX_QcomIndexParamEnableVpp = 0x7F000046, - - /* MBI statistics mode */ - OMX_QcomIndexParamMBIStatisticsMode = 0x7F000047, - - /* Set PictureTypeDecode */ - OMX_QcomIndexConfigPictureTypeDecode = 0x7F000048, - - OMX_QcomIndexConfigH264EntropyCodingCabac = 0x7F000049, - - /* "OMX.QCOM.index.param.video.InputBatch" */ - OMX_QcomIndexParamBatchSize = 0x7F00004A, - - OMX_QcomIndexConfigNumHierPLayers = 0x7F00004B, - - OMX_QcomIndexConfigRectType = 0x7F00004C, - - OMX_QcomIndexConfigBaseLayerId = 0x7F00004E, - - OMX_QcomIndexParamDriverVersion = 0x7F00004F, - - OMX_QcomIndexConfigQp = 0x7F000050, - - OMX_QcomIndexParamVencAspectRatio = 0x7F000051, - - OMX_QTIIndexParamVQZipSEIExtraData = 0x7F000052, - - /* Enable VQZIP SEI NAL type */ - OMX_QTIIndexParamVQZIPSEIType = 0x7F000053, - - OMX_QTIIndexParamPassInputBufferFd = 0x7F000054, - - /* Set Prefer-adaptive playback*/ - /* "OMX.QTI.index.param.video.PreferAdaptivePlayback" */ - OMX_QTIIndexParamVideoPreferAdaptivePlayback = 0x7F000055, - - /* Set time params */ - OMX_QTIIndexConfigSetTimeData = 0x7F000056, - /* Force Compressed format for DPB when resolution <=1080p - * and OPB is cpu_access */ - /* OMX.QTI.index.param.video.ForceCompressedForDPB */ - OMX_QTIIndexParamForceCompressedForDPB = 0x7F000057, - - /* Enable ROI info */ - OMX_QTIIndexParamVideoEnableRoiInfo = 0x7F000058, - - /* Configure ROI info */ - OMX_QTIIndexConfigVideoRoiInfo = 0x7F000059, - - /* Set Low Latency Mode */ - OMX_QTIIndexParamLowLatencyMode = 0x7F00005A, - - /* Force OPB to UnCompressed mode */ - OMX_QTIIndexParamForceUnCompressedForOPB = 0x7F00005B, - -}; - -/** -* This is custom extension to configure Low Latency Mode. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* bLowLatencyMode : Enable/Disable Low Latency mode -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bLowLatencyMode; -} QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE; - -/** -* This is custom extension to configure Encoder Aspect Ratio. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nSARWidth : Horizontal aspect size -* nSARHeight : Vertical aspect size -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_SAR -{ - OMX_U32 nSize; - OMX_U32 nVersion; - OMX_U32 nSARWidth; - OMX_U32 nSARHeight; -} QOMX_EXTNINDEX_VIDEO_VENC_SAR; - -/** -* This is custom extension to configure Hier-p layers. -* This mode configures Hier-p layers dynamically. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nNumHierLayers: Set the number of Hier-p layers for the session -* - This should be less than the MAX Hier-P -* layers set for the session. -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nNumHierLayers; -} QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS; - - -/** -* This is custom extension to configure Hybrid Hier-p settings. -* This mode is different from enabling Hier-p mode. This -* property enables Hier-p encoding with LTR referencing in each -* sub-GOP. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nKeyFrameInterval : Indicates the I frame interval -* nHpLayers : Set the number of Hier-p layers for the session -* - This should be <= 6. (1 Base layer + -* 5 Enhancement layers) -* nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS] : Bitrate to -* be set for each enhancement layer -* nMinQuantizer : minimum session QP -* nMaxQuantizer : Maximun session QP -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nKeyFrameInterval; - OMX_U32 nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS]; - OMX_U32 nMinQuantizer; - OMX_U32 nMaxQuantizer; - OMX_U32 nHpLayers; -} QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE; - -/** - * Encoder Performance Mode. This structure is used to set - * performance mode or power save mode when encoding. The search - * range is modified to save power or improve quality. - * - * STRUCT MEMBERS: - * OMX_U32 nPerfMode : Performance mode: - * 1: MAX_QUALITY - * 2: POWER_SAVE - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_PERFMODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPerfMode; -} QOMX_EXTNINDEX_VIDEO_PERFMODE; - -/** - * Initial QP parameter. This structure is used to enable - * vendor specific extension to let client enable setting - * initial QP values to I P B Frames - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * OMX_U32 nQpI : First Iframe QP - * OMX_U32 nQpP : First Pframe QP - * OMX_U32 nQpB : First Bframe QP - * OMX_U32 bEnableInitQp : Bit field indicating which frame type(s) shall - * use the specified initial QP. - * Bit 0: Enable initial QP for I/IDR - * and use value specified in nInitQpI - * Bit 1: Enable initial QP for P - * and use value specified in nInitQpP - * Bit 2: Enable initial QP for B - * and use value specified in nInitQpB - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_INITIALQP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; - OMX_U32 bEnableInitQp; -} QOMX_EXTNINDEX_VIDEO_INITIALQP; - -/** - * Extension index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required flags and data, if any. - * The format of flags and data being passed is known to - * the client and component apriori. - * - * STRUCT MEMBERS: - * nSize : Size of Structure plus pData size - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * bEnable : Extension index enable (1) or disable (0) - * nFlags : Extension index flags, if any - * nDataSize : Size of the extension index data to follow - * pData : Extension index data, if present. - */ -typedef struct QOMX_EXTNINDEX_PARAMTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_U32 nFlags; - OMX_U32 nDataSize; - OMX_PTR pData; -} QOMX_EXTNINDEX_PARAMTYPE; - -/** - * Range index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required minimum and maximum values - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nMin : Minimum value - * nMax : Maximum value - * nSteSize : Step size - */ -typedef struct QOMX_EXTNINDEX_RANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nMin; - OMX_S32 nMax; - OMX_S32 nStepSize; -} QOMX_EXTNINDEX_RANGETYPE; - -/** - * Specifies LTR mode types. - */ -typedef enum QOMX_VIDEO_LTRMODETYPE -{ - QOMX_VIDEO_LTRMode_Disable = 0x0, /**< LTR encoding is disabled */ - QOMX_VIDEO_LTRMode_Manual = 0x1, /**< In this mode, IL client configures - ** the encoder the LTR count and manually - ** controls the marking and use of LTR - ** frames during video encoding. - */ - QOMX_VIDEO_LTRMode_Auto = 0x2, /**< In this mode, IL client configures - ** the encoder the LTR count and LTR - ** period. The encoder marks LTR frames - ** automatically based on the LTR period - ** during video encoding. IL client controls - ** the use of LTR frames. - */ - QOMX_VIDEO_LTRMode_MAX = 0x7FFFFFFF /** Maximum LTR Mode type */ -} QOMX_VIDEO_LTRMODETYPE; - -/** - * LTR mode index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR mode information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * eLTRMode : Specifies the LTR mode used in encoder - */ -typedef struct QOMX_VIDEO_PARAM_LTRMODE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_LTRMODETYPE eLTRMode; -} QOMX_VIDEO_PARAM_LTRMODE_TYPE; - -/** - * LTR count index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR count information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nCount : Specifies the number of LTR frames stored in the - * encoder component - */ -typedef struct QOMX_VIDEO_PARAM_LTRCOUNT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nCount; -} QOMX_VIDEO_PARAM_LTRCOUNT_TYPE; - - -/** - * This should be used with OMX_QcomIndexParamVideoLTRCount extension. - */ -typedef QOMX_VIDEO_PARAM_LTRCOUNT_TYPE OMX_QCOM_VIDEO_PARAM_LTRCOUNT_TYPE; - -/** - * LTR period index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR period information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nFrames : Specifies the number of frames between two consecutive - * LTR frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE; - -/** - * Marks the next encoded frame as an LTR frame. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be marked - * as reference frame for encoding subsequent frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRMARK_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; -} QOMX_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRMark extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRMARK_TYPE OMX_QCOM_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * Specifies an LTR frame to encode subsequent frames. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be used - as reference frame for encoding subsequent frames. - * nFrames : Specifies the number of subsequent frames to be - encoded using the LTR frame with its identifier - nID as reference frame. Short-term reference frames - will be used thereafter. The value of 0xFFFFFFFF - indicates that all subsequent frames will be - encodedusing this LTR frame as reference frame. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRUSE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRUse extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRUSE_TYPE OMX_QCOM_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * Enumeration used to define the video encoder modes - * - * ENUMS: - * EncoderModeDefault : Default video recording mode. - * All encoder settings made through - * OMX_SetParameter/OMX_SetConfig are applied. No - * parameter is overridden. - * EncoderModeMMS : Video recording mode for MMS (Multimedia Messaging - * Service). This mode is similar to EncoderModeDefault - * except that here the Rate control mode is overridden - * internally and set as a variant of variable bitrate with - * variable frame rate. After this mode is set if the IL - * client tries to set OMX_VIDEO_CONTROLRATETYPE via - * OMX_IndexParamVideoBitrate that would be rejected. For - * this, client should set mode back to EncoderModeDefault - * first and then change OMX_VIDEO_CONTROLRATETYPE. - */ -typedef enum QOMX_VIDEO_ENCODERMODETYPE -{ - QOMX_VIDEO_EncoderModeDefault = 0x00, - QOMX_VIDEO_EncoderModeMMS = 0x01, - QOMX_VIDEO_EncoderModeMax = 0x7FFFFFFF -} QOMX_VIDEO_ENCODERMODETYPE; - -/** - * This structure is used to set the video encoder mode. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nMode : defines the video encoder mode - */ -typedef struct QOMX_VIDEO_PARAM_ENCODERMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_ENCODERMODETYPE nMode; -} QOMX_VIDEO_PARAM_ENCODERMODETYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_SYNTAXHDRTYPE extension. This parameter can be queried - * during the loaded state. - */ - -typedef struct QOMX_VIDEO_SYNTAXHDRTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBytes; /** The number of bytes filled in to the buffer */ - OMX_U8 data[1]; /** Buffer to store the header information */ -} QOMX_VIDEO_SYNTAXHDRTYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_TEMPORALSPATIALTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for setting MaxQP from the application. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_TEMPORALSPATIALTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nTSFactor; /** Temoral spatial tradeoff factor value in 0-100 */ -} QOMX_VIDEO_TEMPORALSPATIALTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_INTRAPERIODTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_INTRAPERIODTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nIDRPeriod; /** This specifies coding a frame as IDR after every nPFrames - of intra frames. If this parameter is set to 0, only the - first frame of the encode session is an IDR frame. This - field is ignored for non-AVC codecs and is used only for - codecs that support IDR Period */ - OMX_U32 nPFrames; /** The number of "P" frames between two "I" frames */ - OMX_U32 nBFrames; /** The number of "B" frames between two "I" frames */ -} QOMX_VIDEO_INTRAPERIODTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is used for the buffer negotiation - * with other clients. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBufferOccupancy; /** The number of bytes to be set for the buffer occupancy */ -} OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily used for the dynamic/random - * intrarefresh. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nRirMBs; /** The number of MBs to be set for intrarefresh */ -} OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE; - - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_QPRANGE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for the min/max QP to be set from the application. This - * is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_QPRANGE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nMinQP; /** The number for minimum quantization parameter */ - OMX_U32 nMaxQP; /** The number for maximum quantization parameter */ -} OMX_QCOM_VIDEO_CONFIG_QPRANGE; - -/** - * This structure describes the parameters for the - * OMX_QcomIndexParamH264AUDelimiter extension. It enables/disables - * the AU delimiters in the H264 stream, which is used by WFD. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_H264_AUD -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_CONFIG_H264_AUD; - -typedef enum QOMX_VIDEO_PERF_LEVEL -{ - OMX_QCOM_PerfLevelNominal, - OMX_QCOM_PerfLevelTurbo -} QOMX_VIDEO_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_PARAM_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL; - -typedef enum QOMX_VIDEO_PICTURE_TYPE_DECODE -{ - OMX_QCOM_PictypeDecode_IPB, - OMX_QCOM_PictypeDecode_I -} QOMX_VIDEO_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPictureTypeDecode extension. It - * will set the picture type decode specified by eDecodeType. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PICTURE_TYPE_DECODE eDecodeType; /** Decode type */ -} OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamH264VUITimingInfo extension. It - * will enable/disable the VUI timing info. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamVQZIPSEIType extension. It - * will enable/disable the VQZIP SEI info. - */ -typedef struct OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPeakBitrate extension. It will - * set the peak bitrate specified by nPeakBitrate. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPeakBitrate; /** Peak bitrate value */ -} OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceCompressedForDPB extension. Enabling - * this extension will force the split mode DPB(compressed)/OPB(Linear) - * for all resolutions.On some chipsets preferred mode would be combined - * Linear for both DPB/OPB to save memory. For example on 8996 preferred mode - * would be combined linear for resolutions <= 1080p . - * Enabling this might save power but with the cost - * of increased memory i.e almost double the number on output YUV buffers. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceUnCompressedForOPB extension. Enabling this - * extension will force the OPB to be linear for the current video session. - * If this property is not set, then the OPB will be set to linear or compressed - * based on resolution selected and/or if cpu access is requested on the - * OPB buffer. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE { - OMX_U32 nSize; /** Sizeo f the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE; - -typedef struct OMX_VENDOR_EXTRADATATYPE { - OMX_U32 nPortIndex; - OMX_U32 nDataSize; - OMX_U8 *pData; // cdata (codec_data/extradata) -} OMX_VENDOR_EXTRADATATYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_VENDOR_VIDEOFRAMERATE extension. This parameter can be set - * dynamically during any state except the state invalid. This is - * used for frame rate to be set from the application. This - * is set on the in port. - */ -typedef struct OMX_VENDOR_VIDEOFRAMERATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nFps; /** Frame rate value */ - OMX_BOOL bEnabled; /** Flag to enable or disable client's frame rate value */ -} OMX_VENDOR_VIDEOFRAMERATE; - -typedef enum OMX_INDEXVENDORTYPE { - OMX_IndexVendorFileReadInputFilename = 0xFF000001, - OMX_IndexVendorParser3gpInputFilename = 0xFF000002, - OMX_IndexVendorVideoExtraData = 0xFF000003, - OMX_IndexVendorAudioExtraData = 0xFF000004, - OMX_IndexVendorVideoFrameRate = 0xFF000005, -} OMX_INDEXVENDORTYPE; - -typedef enum OMX_QCOM_VC1RESOLUTIONTYPE -{ - OMX_QCOM_VC1_PICTURE_RES_1x1, - OMX_QCOM_VC1_PICTURE_RES_2x1, - OMX_QCOM_VC1_PICTURE_RES_1x2, - OMX_QCOM_VC1_PICTURE_RES_2x2 -} OMX_QCOM_VC1RESOLUTIONTYPE; - -typedef enum OMX_QCOM_INTERLACETYPE -{ - OMX_QCOM_InterlaceFrameProgressive, - OMX_QCOM_InterlaceInterleaveFrameTopFieldFirst, - OMX_QCOM_InterlaceInterleaveFrameBottomFieldFirst, - OMX_QCOM_InterlaceFrameTopFieldFirst, - OMX_QCOM_InterlaceFrameBottomFieldFirst, - OMX_QCOM_InterlaceFieldTop, - OMX_QCOM_InterlaceFieldBottom -}OMX_QCOM_INTERLACETYPE; - -typedef struct OMX_QCOM_PARAM_VIDEO_INTERLACETYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_BOOL bInterlace; /** Interlace content **/ -}OMX_QCOM_PARAM_VIDEO_INTERLACETYPE; - -typedef struct OMX_QCOM_CONFIG_INTERLACETYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOM_INTERLACETYPE eInterlaceType; -}OMX_QCOM_CONFIG_INTERLACETYPE; - -#define MAX_PAN_SCAN_WINDOWS 4 - -typedef struct OMX_QCOM_PANSCAN -{ - OMX_U32 numWindows; - OMX_QCOMRectangle window[MAX_PAN_SCAN_WINDOWS]; -} OMX_QCOM_PANSCAN; - -typedef struct OMX_QCOM_ASPECT_RATIO -{ - OMX_U32 aspectRatioX; - OMX_U32 aspectRatioY; -} OMX_QCOM_ASPECT_RATIO; - -typedef struct OMX_QCOM_DISPLAY_ASPECT_RATIO -{ - OMX_U32 displayVerticalSize; - OMX_U32 displayHorizontalSize; -} OMX_QCOM_DISPLAY_ASPECT_RATIO; - -typedef struct OMX_QCOM_FRAME_PACK_ARRANGEMENT -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 id; - OMX_U32 cancel_flag; - OMX_U32 type; - OMX_U32 quincunx_sampling_flag; - OMX_U32 content_interpretation_type; - OMX_U32 spatial_flipping_flag; - OMX_U32 frame0_flipped_flag; - OMX_U32 field_views_flag; - OMX_U32 current_frame_is_frame0_flag; - OMX_U32 frame0_self_contained_flag; - OMX_U32 frame1_self_contained_flag; - OMX_U32 frame0_grid_position_x; - OMX_U32 frame0_grid_position_y; - OMX_U32 frame1_grid_position_x; - OMX_U32 frame1_grid_position_y; - OMX_U32 reserved_byte; - OMX_U32 repetition_period; - OMX_U32 extension_flag; -} OMX_QCOM_FRAME_PACK_ARRANGEMENT; - -typedef struct OMX_QCOM_EXTRADATA_QP -{ - OMX_U32 nQP; -} OMX_QCOM_EXTRADATA_QP; - -typedef struct OMX_QCOM_EXTRADATA_BITS_INFO -{ - OMX_U32 header_bits; - OMX_U32 frame_bits; -} OMX_QCOM_EXTRADATA_BITS_INFO; - -typedef struct OMX_QCOM_EXTRADATA_USERDATA { - OMX_U32 type; - OMX_U32 data[1]; -} OMX_QCOM_EXTRADATA_USERDATA; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEINFO -{ - // common frame meta data. interlace related info removed - OMX_VIDEO_PICTURETYPE ePicType; - OMX_QCOM_INTERLACETYPE interlaceType; - OMX_QCOM_PANSCAN panScan; - OMX_QCOM_ASPECT_RATIO aspectRatio; - OMX_QCOM_DISPLAY_ASPECT_RATIO displayAspectRatio; - OMX_U32 nConcealedMacroblocks; - OMX_U32 nFrameRate; - OMX_TICKS nTimeStamp; -} OMX_QCOM_EXTRADATA_FRAMEINFO; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEDIMENSION -{ - /** Frame Dimensions added to each YUV buffer */ - OMX_U32 nDecWidth; /** Width rounded to multiple of 16 */ - OMX_U32 nDecHeight; /** Height rounded to multiple of 16 */ - OMX_U32 nActualWidth; /** Actual Frame Width */ - OMX_U32 nActualHeight; /** Actual Frame Height */ - -} OMX_QCOM_EXTRADATA_FRAMEDIMENSION; - -typedef struct OMX_QCOM_H264EXTRADATA -{ - OMX_U64 seiTimeStamp; -} OMX_QCOM_H264EXTRADATA; - -typedef struct OMX_QCOM_VC1EXTRADATA -{ - OMX_U32 nVC1RangeY; - OMX_U32 nVC1RangeUV; - OMX_QCOM_VC1RESOLUTIONTYPE eVC1PicResolution; -} OMX_QCOM_VC1EXTRADATA; - -typedef union OMX_QCOM_EXTRADATA_CODEC_DATA -{ - OMX_QCOM_H264EXTRADATA h264ExtraData; - OMX_QCOM_VC1EXTRADATA vc1ExtraData; -} OMX_QCOM_EXTRADATA_CODEC_DATA; - -typedef struct OMX_QCOM_EXTRADATA_MBINFO -{ - OMX_U32 nFormat; - OMX_U32 nDataSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_MBINFO; - -typedef struct OMX_QCOM_EXTRADATA_VQZIPSEI { - OMX_U32 nSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_VQZIPSEI; - -typedef struct OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableRoiInfo; -} OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO; - -typedef struct OMX_QTI_VIDEO_CONFIG_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nUpperQpOffset; - OMX_S32 nLowerQpOffset; - OMX_BOOL bUseRoiInfo; - OMX_S32 nRoiMBInfoSize; - OMX_PTR pRoiMBInfo; -} OMX_QTI_VIDEO_CONFIG_ROIINFO; - -typedef enum OMX_QCOM_EXTRADATATYPE -{ - OMX_ExtraDataFrameInfo = 0x7F000001, - OMX_ExtraDataH264 = 0x7F000002, - OMX_ExtraDataVC1 = 0x7F000003, - OMX_ExtraDataFrameDimension = 0x7F000004, - OMX_ExtraDataVideoEncoderSliceInfo = 0x7F000005, - OMX_ExtraDataConcealMB = 0x7F000006, - OMX_ExtraDataInterlaceFormat = 0x7F000007, - OMX_ExtraDataPortDef = 0x7F000008, - OMX_ExtraDataMP2ExtnData = 0x7F000009, - OMX_ExtraDataMP2UserData = 0x7F00000a, - OMX_ExtraDataVideoLTRInfo = 0x7F00000b, - OMX_ExtraDataFramePackingArrangement = 0x7F00000c, - OMX_ExtraDataQP = 0x7F00000d, - OMX_ExtraDataInputBitsInfo = 0x7F00000e, - OMX_ExtraDataVideoEncoderMBInfo = 0x7F00000f, - OMX_ExtraDataVQZipSEI = 0x7F000010, -} OMX_QCOM_EXTRADATATYPE; - -typedef struct OMX_STREAMINTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bInterlaceFormat; - OMX_U32 nInterlaceFormats; -} OMX_STREAMINTERLACEFORMAT; - -typedef enum OMX_INTERLACETYPE -{ - OMX_InterlaceFrameProgressive, - OMX_InterlaceInterleaveFrameTopFieldFirst, - OMX_InterlaceInterleaveFrameBottomFieldFirst, - OMX_InterlaceFrameTopFieldFirst, - OMX_InterlaceFrameBottomFieldFirst -} OMX_INTERLACES; - - -#define OMX_EXTRADATA_HEADER_SIZE 20 - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum QOMX_VIDEO_AVCPROFILETYPE { - QOMX_VIDEO_AVCProfileBaseline = OMX_VIDEO_AVCProfileBaseline, - QOMX_VIDEO_AVCProfileMain = OMX_VIDEO_AVCProfileMain, - QOMX_VIDEO_AVCProfileExtended = OMX_VIDEO_AVCProfileExtended, - QOMX_VIDEO_AVCProfileHigh = OMX_VIDEO_AVCProfileHigh, - QOMX_VIDEO_AVCProfileHigh10 = OMX_VIDEO_AVCProfileHigh10, - QOMX_VIDEO_AVCProfileHigh422 = OMX_VIDEO_AVCProfileHigh422, - QOMX_VIDEO_AVCProfileHigh444 = OMX_VIDEO_AVCProfileHigh444, - /* QCom specific profile indexes */ - QOMX_VIDEO_AVCProfileConstrained = OMX_VIDEO_AVCProfileVendorStartUnused, - QOMX_VIDEO_AVCProfileConstrainedBaseline, - QOMX_VIDEO_AVCProfileConstrainedHigh, -} QOMX_VIDEO_AVCPROFILETYPE; - - -/** - * H.264 MVC Profiles - */ -typedef enum QOMX_VIDEO_MVCPROFILETYPE { - QOMX_VIDEO_MVCProfileStereoHigh = 0x1, - QOMX_VIDEO_MVCProfileMultiViewHigh = 0x2, - QOMX_VIDEO_MVCProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCPROFILETYPE; - -/** - * H.264 MVC Levels - */ -typedef enum QOMX_VIDEO_MVCLEVELTYPE { - QOMX_VIDEO_MVCLevel1 = 0x01, /**< Level 1 */ - QOMX_VIDEO_MVCLevel1b = 0x02, /**< Level 1b */ - QOMX_VIDEO_MVCLevel11 = 0x04, /**< Level 1.1 */ - QOMX_VIDEO_MVCLevel12 = 0x08, /**< Level 1.2 */ - QOMX_VIDEO_MVCLevel13 = 0x10, /**< Level 1.3 */ - QOMX_VIDEO_MVCLevel2 = 0x20, /**< Level 2 */ - QOMX_VIDEO_MVCLevel21 = 0x40, /**< Level 2.1 */ - QOMX_VIDEO_MVCLevel22 = 0x80, /**< Level 2.2 */ - QOMX_VIDEO_MVCLevel3 = 0x100, /**< Level 3 */ - QOMX_VIDEO_MVCLevel31 = 0x200, /**< Level 3.1 */ - QOMX_VIDEO_MVCLevel32 = 0x400, /**< Level 3.2 */ - QOMX_VIDEO_MVCLevel4 = 0x800, /**< Level 4 */ - QOMX_VIDEO_MVCLevel41 = 0x1000, /**< Level 4.1 */ - QOMX_VIDEO_MVCLevel42 = 0x2000, /**< Level 4.2 */ - QOMX_VIDEO_MVCLevel5 = 0x4000, /**< Level 5 */ - QOMX_VIDEO_MVCLevel51 = 0x8000, /**< Level 5.1 */ - QOMX_VIDEO_MVCLevelKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCLevelVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCLevelMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCLEVELTYPE; - -/** - * DivX Versions - */ -typedef enum QOMX_VIDEO_DIVXFORMATTYPE { - QOMX_VIDEO_DIVXFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_DIVXFormat311 = 0x02, /**< DivX 3.11 */ - QOMX_VIDEO_DIVXFormat4 = 0x04, /**< DivX 4 */ - QOMX_VIDEO_DIVXFormat5 = 0x08, /**< DivX 5 */ - QOMX_VIDEO_DIVXFormat6 = 0x10, /**< DivX 6 */ - QOMX_VIDEO_DIVXFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXFORMATTYPE; - -/** - * DivX profile types, each profile indicates support for - * various performance bounds. - */ -typedef enum QOMX_VIDEO_DIVXPROFILETYPE { - QOMX_VIDEO_DivXProfileqMobile = 0x01, /**< qMobile Profile */ - QOMX_VIDEO_DivXProfileMobile = 0x02, /**< Mobile Profile */ - QOMX_VIDEO_DivXProfileMT = 0x04, /**< Mobile Theatre Profile */ - QOMX_VIDEO_DivXProfileHT = 0x08, /**< Home Theatre Profile */ - QOMX_VIDEO_DivXProfileHD = 0x10, /**< High Definition Profile */ - QOMX_VIDEO_DIVXProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXPROFILETYPE; - -/** - * DivX Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of DivX stream / data - * eProfile : Profile of DivX stream / data - */ -typedef struct QOMX_VIDEO_PARAM_DIVXTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_DIVXFORMATTYPE eFormat; - QOMX_VIDEO_DIVXPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_DIVXTYPE; - - - -/** - * VP Versions - */ -typedef enum QOMX_VIDEO_VPFORMATTYPE { - QOMX_VIDEO_VPFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_VPFormat6 = 0x02, /**< VP6 Video Format */ - QOMX_VIDEO_VPFormat7 = 0x04, /**< VP7 Video Format */ - QOMX_VIDEO_VPFormat8 = 0x08, /**< VP8 Video Format */ - QOMX_VIDEO_VPFormat9 = 0x10, /**< VP9 Video Format */ - QOMX_VIDEO_VPFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_VPFORMATTYPE; - -/** - * VP profile types, each profile indicates support for various - * encoding tools. - */ -typedef enum QOMX_VIDEO_VPPROFILETYPE { - QOMX_VIDEO_VPProfileSimple = 0x01, /**< Simple Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileAdvanced = 0x02, /**< Advanced Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileVersion0 = 0x04, /**< Version 0, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion1 = 0x08, /**< Version 1, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion2 = 0x10, /**< Version 2, applies to VP8 only */ - QOMX_VIDEO_VPProfileVersion3 = 0x20, /**< Version 3, applies to VP8 only */ - QOMX_VIDEO_VPProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_VPPROFILETYPE; - -/** - * VP Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Format of VP stream / data - * eProfile : Profile or Version of VP stream / data - */ -typedef struct QOMX_VIDEO_PARAM_VPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_VPFORMATTYPE eFormat; - QOMX_VIDEO_VPPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_VPTYPE; - -/** - * Spark Versions - */ -typedef enum QOMX_VIDEO_SPARKFORMATTYPE { - QOMX_VIDEO_SparkFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_SparkFormat0 = 0x02, /**< Video Format Version 0 */ - QOMX_VIDEO_SparkFormat1 = 0x04, /**< Video Format Version 1 */ - QOMX_VIDEO_SparkFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_SparkFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_SparkFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_SPARKFORMATTYPE; - -/** - * Spark Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of Spark stream / data - */ -typedef struct QOMX_VIDEO_PARAM_SPARKTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_SPARKFORMATTYPE eFormat; -} QOMX_VIDEO_PARAM_SPARKTYPE; - - -typedef struct QOMX_VIDEO_QUERY_DECODER_INSTANCES { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumOfInstances; -} QOMX_VIDEO_QUERY_DECODER_INSTANCES; - -typedef struct QOMX_ENABLETYPE { - OMX_BOOL bEnable; -} QOMX_ENABLETYPE; - -typedef enum QOMX_VIDEO_EVENTS { - OMX_EventIndexsettingChanged = OMX_EventVendorStartUnused -} QOMX_VIDEO_EVENTS; - -typedef enum QOMX_VIDEO_PICTURE_ORDER { - QOMX_VIDEO_DISPLAY_ORDER = 0x1, - QOMX_VIDEO_DECODE_ORDER = 0x2 -} QOMX_VIDEO_PICTURE_ORDER; - -typedef struct QOMX_VIDEO_DECODER_PICTURE_ORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_PICTURE_ORDER eOutputPictureOrder; -} QOMX_VIDEO_DECODER_PICTURE_ORDER; - -typedef struct QOMX_INDEXEXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; - OMX_INDEXTYPE nIndex; -} QOMX_INDEXEXTRADATATYPE; - -typedef struct QOMX_INDEXTIMESTAMPREORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXTIMESTAMPREORDER; - -typedef struct QOMX_INDEXDOWNSCALAR { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXDOWNSCALAR; - -typedef struct QOMX_VIDEO_CUSTOM_BUFFERSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBufferSize; -} QOMX_VIDEO_CUSTOM_BUFFERSIZE; - -#define OMX_QCOM_INDEX_PARAM_VIDEO_SYNCFRAMEDECODINGMODE "OMX.QCOM.index.param.video.SyncFrameDecodingMode" -#define OMX_QCOM_INDEX_PARAM_INDEXEXTRADATA "OMX.QCOM.index.param.IndexExtraData" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SLICEDELIVERYMODE "OMX.QCOM.index.param.SliceDeliveryMode" -#define OMX_QCOM_INDEX_PARAM_VIDEO_FRAMEPACKING_EXTRADATA "OMX.QCOM.index.param.video.FramePackingExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_QP_EXTRADATA "OMX.QCOM.index.param.video.QPExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_INPUTBITSINFO_EXTRADATA "OMX.QCOM.index.param.video.InputBitsInfoExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_EXTNUSER_EXTRADATA "OMX.QCOM.index.param.video.ExtnUserExtraData" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_FRAMEPACKING_INFO "OMX.QCOM.index.config.video.FramePackingInfo" -#define OMX_QCOM_INDEX_PARAM_VIDEO_MPEG2SEQDISP_EXTRADATA "OMX.QCOM.index.param.video.Mpeg2SeqDispExtraData" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_HIERSTRUCTURE "OMX.QCOM.index.param.video.HierStructure" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRCOUNT "OMX.QCOM.index.param.video.LTRCount" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRPERIOD "OMX.QCOM.index.param.video.LTRPeriod" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE "OMX.QCOM.index.config.video.LTRUse" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRMARK "OMX.QCOM.index.config.video.LTRMark" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_HIER_P_LAYERS "OMX.QCOM.index.config.video.hierplayers" -#define OMX_QCOM_INDEX_CONFIG_RECTANGLE_TYPE "OMX.QCOM.index.config.video.rectangle" -#define OMX_QCOM_INDEX_PARAM_VIDEO_BASE_LAYER_ID "OMX.QCOM.index.param.video.baselayerid" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_QP "OMX.QCOM.index.config.video.qp" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SAR "OMX.QCOM.index.param.video.sar" -#define OMX_QTI_INDEX_PARAM_VIDEO_LOW_LATENCY "OMX.QTI.index.param.video.LowLatency" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_PASSINPUTBUFFERFD "OMX.QCOM.index.param.video.PassInputBufferFd" -#define OMX_QTI_INDEX_PARAM_VIDEO_PREFER_ADAPTIVE_PLAYBACK "OMX.QTI.index.param.video.PreferAdaptivePlayback" -#define OMX_QTI_INDEX_CONFIG_VIDEO_SETTIMEDATA "OMX.QTI.index.config.video.settimedata" -#define OMX_QTI_INDEX_PARAM_VIDEO_FORCE_COMPRESSED_FOR_DPB "OMX.QTI.index.param.video.ForceCompressedForDPB" -#define OMX_QTI_INDEX_PARAM_VIDEO_ENABLE_ROIINFO "OMX.QTI.index.param.enableRoiInfo" -#define OMX_QTI_INDEX_CONFIG_VIDEO_ROIINFO "OMX.QTI.index.config.RoiInfo" - -typedef enum { - QOMX_VIDEO_FRAME_PACKING_CHECKERBOARD = 0, - QOMX_VIDEO_FRAME_PACKING_COLUMN_INTERLEAVE = 1, - QOMX_VIDEO_FRAME_PACKING_ROW_INTERLEAVE = 2, - QOMX_VIDEO_FRAME_PACKING_SIDE_BY_SIDE = 3, - QOMX_VIDEO_FRAME_PACKING_TOP_BOTTOM = 4, - QOMX_VIDEO_FRAME_PACKING_TEMPORAL = 5, -} QOMX_VIDEO_FRAME_PACKING_ARRANGEMENT; - -typedef enum { - QOMX_VIDEO_CONTENT_UNSPECIFIED = 0, - QOMX_VIDEO_CONTENT_LR_VIEW = 1, - QOMX_VIDEO_CONTENT_RL_VIEW = 2, -} QOMX_VIDEO_CONTENT_INTERPRETATION; - -/** - * Specifies the extended picture types. These values should be - * OR'd along with the types defined in OMX_VIDEO_PICTURETYPE to - * signal all pictures types which are allowed. - * - * ENUMS: - * H.264 Specific Picture Types: IDR - */ -typedef enum QOMX_VIDEO_PICTURETYPE { - QOMX_VIDEO_PictureTypeIDR = OMX_VIDEO_PictureTypeVendorStartUnused + 0x1000 -} QOMX_VIDEO_PICTURETYPE; - -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION "OMX.QCOM.index.config.activeregiondetection" -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION_STATUS "OMX.QCOM.index.config.activeregiondetectionstatus" -#define OMX_QCOM_INDEX_CONFIG_SCALING_MODE "OMX.QCOM.index.config.scalingmode" -#define OMX_QCOM_INDEX_CONFIG_NOISEREDUCTION "OMX.QCOM.index.config.noisereduction" -#define OMX_QCOM_INDEX_CONFIG_IMAGEENHANCEMENT "OMX.QCOM.index.config.imageenhancement" -#define OMX_QCOM_INDEX_PARAM_HELDBUFFERCOUNT "OMX.QCOM.index.param.HeldBufferCount" /**< reference: QOMX_HELDBUFFERCOUNTTYPE */ - - -typedef struct QOMX_RECTTYPE { - OMX_S32 nLeft; - OMX_S32 nTop; - OMX_U32 nWidth; - OMX_U32 nHeight; -} QOMX_RECTTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - QOMX_RECTTYPE sROI; - OMX_U32 nNumExclusionRegions; - QOMX_RECTTYPE sExclusionRegions[1]; -} QOMX_ACTIVEREGIONDETECTIONTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTION_STATUSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bDetected; - QOMX_RECTTYPE sDetectedRegion; -} QOMX_ACTIVEREGIONDETECTION_STATUSTYPE; - -typedef enum QOMX_SCALE_MODETYPE { - QOMX_SCALE_MODE_Normal, - QOMX_SCALE_MODE_Anamorphic, - QOMX_SCALE_MODE_Max = 0x7FFFFFFF -} QOMX_SCALE_MODETYPE; - -typedef struct QOMX_SCALINGMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - QOMX_SCALE_MODETYPE eScaleMode; -} QOMX_SCALINGMODETYPE; - -typedef struct QOMX_NOISEREDUCTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nNoiseReduction; -} QOMX_NOISEREDUCTIONTYPE; - -typedef struct QOMX_IMAGEENHANCEMENTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nImageEnhancement; -} QOMX_IMAGEENHANCEMENTTYPE; - -/* - * these are part of OMX1.2 but JB MR2 branch doesn't have them defined - * OMX_IndexParamInterlaceFormat - * OMX_INTERLACEFORMATTYPE - */ -#ifndef OMX_IndexParamInterlaceFormat -#define OMX_IndexParamInterlaceFormat (0x7FF00000) -typedef struct OMX_INTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFormat; - OMX_TICKS nTimeStamp; -} OMX_INTERLACEFORMATTYPE; -#endif - -/** - * This structure is used to indicate the maximum number of buffers - * that a port will hold during data flow. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nHeldBufferCount : Read-only, maximum number of buffers that will be held - */ -typedef struct QOMX_HELDBUFFERCOUNTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nHeldBufferCount; -} QOMX_HELDBUFFERCOUNTTYPE; - -typedef enum QOMX_VIDEO_HIERARCHICALCODINGTYPE { - QOMX_HIERARCHICALCODING_P = 0x01, - QOMX_HIERARCHICALCODING_B = 0x02, -} QOMX_VIDEO_HIERARCHICALCODINGTYPE; - -typedef struct QOMX_VIDEO_HIERARCHICALLAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumLayers; - QOMX_VIDEO_HIERARCHICALCODINGTYPE eHierarchicalCodingType; -} QOMX_VIDEO_HIERARCHICALLAYERS; - -typedef struct QOMX_VIDEO_H264ENTROPYCODINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bCabac; - OMX_U32 nCabacInitIdc; -} QOMX_VIDEO_H264ENTROPYCODINGTYPE; - - -/* VIDEO POSTPROCESSING CTRLS AND ENUMS */ -#define QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ 256 -#define VPP_HQV_CONTROL_GLOBAL_START (VPP_HQV_CONTROL_CUST + 1) - -typedef enum QOMX_VPP_HQV_MODE { - VPP_HQV_MODE_OFF, - VPP_HQV_MODE_AUTO, - VPP_HQV_MODE_MANUAL, - VPP_HQV_MODE_MAX -} QOMX_VPP_HQV_MODE; - -typedef enum QOMX_VPP_HQVCONTROLTYPE { - VPP_HQV_CONTROL_CADE = 0x1, - VPP_HQV_CONTROL_CNR = 0x04, - VPP_HQV_CONTROL_AIE = 0x05, - VPP_HQV_CONTROL_FRC = 0x06, - VPP_HQV_CONTROL_CUST = 0x07, - VPP_HQV_CONTROL_GLOBAL_DEMO = VPP_HQV_CONTROL_GLOBAL_START, - VPP_HQV_CONTROL_MAX, -} QOMX_VPP_HQVCONTROLTYPE; - -typedef enum QOMX_VPP_HQV_HUE_MODE { - VPP_HQV_HUE_MODE_OFF, - VPP_HQV_HUE_MODE_ON, - VPP_HQV_HUE_MODE_MAX, -} QOMX_VPP_HQV_HUE_MODE; - -typedef enum QOMX_VPP_HQV_FRC_MODE { - VPP_HQV_FRC_MODE_OFF, - VPP_HQV_FRC_MODE_LOW, - VPP_HQV_FRC_MODE_MED, - VPP_HQV_FRC_MODE_HIGH, - VPP_HQV_FRC_MODE_MAX, -} QOMX_VPP_HQV_FRC_MODE; - - -typedef struct QOMX_VPP_HQVCTRL_CADE { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; - OMX_S32 contrast; - OMX_S32 saturation; -} QOMX_VPP_HQVCTRL_CADE; - -typedef struct QOMX_VPP_HQVCTRL_CNR { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; -} QOMX_VPP_HQVCTRL_CNR; - -typedef struct QOMX_VPP_HQVCTRL_AIE { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQV_HUE_MODE hue_mode; - OMX_U32 cade_level; - OMX_U32 ltm_level; -} QOMX_VPP_HQVCTRL_AIE; - -typedef struct QOMX_VPP_HQVCTRL_CUSTOM { - OMX_U32 id; - OMX_U32 len; - OMX_U8 data[QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ]; -} QOMX_VPP_HQVCTRL_CUSTOM; - -typedef struct QOMX_VPP_HQVCTRL_GLOBAL_DEMO { - OMX_U32 process_percent; -} QOMX_VPP_HQVCTRL_GLOBAL_DEMO; - -typedef struct QOMX_VPP_HQVCTRL_FRC { - QOMX_VPP_HQV_FRC_MODE mode; -} QOMX_VPP_HQVCTRL_FRC; - -typedef struct QOMX_VPP_HQVCONTROL { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQVCONTROLTYPE ctrl_type; - union { - QOMX_VPP_HQVCTRL_CADE cade; - QOMX_VPP_HQVCTRL_CNR cnr; - QOMX_VPP_HQVCTRL_AIE aie; - QOMX_VPP_HQVCTRL_CUSTOM custom; - QOMX_VPP_HQVCTRL_GLOBAL_DEMO global_demo; - QOMX_VPP_HQVCTRL_FRC frc; - }; -} QOMX_VPP_HQVCONTROL; - -/* STRUCTURE TO TURN VPP ON */ -typedef struct QOMX_VPP_ENABLE { - OMX_BOOL enable_vpp; -} QOMX_VPP_ENABLE; - -typedef enum OMX_QOMX_VIDEO_MBISTATISTICSTYPE { - QOMX_MBI_STATISTICS_MODE_DEFAULT = 0, - QOMX_MBI_STATISTICS_MODE_1 = 0x01, - QOMX_MBI_STATISTICS_MODE_2 = 0x02, -} OMX_QOMX_VIDEO_MBISTATISTICSTYPE; - -typedef struct OMX_QOMX_VIDEO_MBI_STATISTICS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_QOMX_VIDEO_MBISTATISTICSTYPE eMBIStatisticsType; -} OMX_QOMX_VIDEO_MBI_STATISTICS; - -typedef struct QOMX_VIDEO_BATCHSIZETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBatchSize; -} QOMX_VIDEO_BATCHSIZETYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __OMX_QCOM_EXTENSIONS_H__ */ diff --git a/third_party/openmax/include/OMX_Skype_VideoExtensions.h b/third_party/openmax/include/OMX_Skype_VideoExtensions.h deleted file mode 100644 index 5cc832930f..0000000000 --- a/third_party/openmax/include/OMX_Skype_VideoExtensions.h +++ /dev/null @@ -1,155 +0,0 @@ -/*@@@+++@@@@****************************************************************** - - Microsoft Skype Engineering - Copyright (C) 2014 Microsoft Corporation. - -MIT License - -Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - -*@@@---@@@@******************************************************************/ - - -#ifndef __OMX_SKYPE_VIDEOEXTENSIONS_H__ -#define __OMX_SKYPE_VIDEOEXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" -{ -#endif - -#include - -#pragma pack(push, 1) - - -typedef enum OMX_SKYPE_VIDEO_SliceControlMode -{ - OMX_SKYPE_VIDEO_SliceControlModeNone = 0, - OMX_SKYPE_VIDEO_SliceControlModeMB = 1, - OMX_SKYPE_VIDEO_SliceControlModeByte = 2, - OMX_SKYPE_VIDEO_SliceControlModMBRow = 3, -} OMX_SKYPE_VIDEO_SliceControlMode; - - -typedef enum OMX_SKYPE_VIDEO_HierarType -{ - OMX_SKYPE_VIDEO_HierarType_P = 0x01, - OMX_SKYPE_VIDEO_HierarType_B = 0x02, -} OMX_SKYPE_VIDEO_HIERAR_HierarType; - -typedef enum OMX_VIDEO_EXTENSION_AVCPROFILETYPE -{ - OMX_VIDEO_EXT_AVCProfileConstrainedBaseline = 0x01, - OMX_VIDEO_EXT_AVCProfileConstrainedHigh = 0x02, -} OMX_VIDEO_EXTENSION_AVCPROFILETYPE; - -typedef struct OMX_SKYPE_VIDEO_ENCODERPARAMS { - OMX_BOOL bLowLatency; - OMX_BOOL bUseExtendedProfile; - OMX_BOOL bSequenceHeaderWithIDR; - OMX_VIDEO_EXTENSION_AVCPROFILETYPE eProfile; - OMX_U32 nLTRFrames; - OMX_SKYPE_VIDEO_HierarType eHierarType; - OMX_U32 nMaxTemporalLayerCount; - OMX_SKYPE_VIDEO_SliceControlMode eSliceControlMode; - OMX_U32 nSarIndex; - OMX_U32 nSarWidth; - OMX_U32 nSarHeight; -} OMX_SKYPE_VIDEO_ENCODERPARAMS; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERSETTING { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERPARAMS stEncParam; -} OMX_SKYPE_VIDEO_PARAM_ENCODESETTING; - -typedef struct OMX_SKYPE_VIDEO_ENCODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_U32 nMaxTemporaLayerCount; - OMX_U32 nMaxRefFrames; - OMX_U32 nMaxLTRFrames; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nSliceControlModesBM; - OMX_U32 nMaxMacroblockProcessingRate; - OMX_U32 xMinScaleFactor; -} OMX_SKYPE_VIDEO_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERCAP stEncCap; -} OMX_SKYPE_VIDEO_PARAM_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_DECODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nMaxMacroblockProcessingRate; -} OMX_SKYPE_VIDEO_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DECODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_DECODERCAP stDecoderCap; -} OMX_SKYPE_VIDEO_PARAM_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_QP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQP; -} OMX_SKYPE_VIDEO_CONFIG_QP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPID; -} OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DRIVERVER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U64 nDriverVersion; -} OMX_SKYPE_VIDEO_PARAM_DRIVERVER; - -typedef enum OMX_SKYPE_VIDEO_DownScaleFactor -{ - OMX_SKYPE_VIDEO_DownScaleFactor_1_1 = 0, - OMX_SKYPE_VIDEO_DownScaleFactor_Equal_AR = 1, - OMX_SKYPE_VIDEO_DownScaleFactor_Any = 2, -} OMX_SKYPE_VIDEO_DownScaleFactor; - -#pragma pack(pop) - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/third_party/openmax/include/OMX_Types.h b/third_party/openmax/include/OMX_Types.h deleted file mode 100644 index 3b9fab4fc2..0000000000 --- a/third_party/openmax/include/OMX_Types.h +++ /dev/null @@ -1,359 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Types.h - OpenMax IL version 1.1.2 - * The OMX_Types header file contains the primitive type definitions used by - * the core, the application and the component. This file may need to be - * modified to be used on systems that do not have "char" set to 8 bits, - * "short" set to 16 bits and "long" set to 32 bits. - */ - -#ifndef OMX_Types_h -#define OMX_Types_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** The OMX_API and OMX_APIENTRY are platform specific definitions used - * to declare OMX function prototypes. They are modified to meet the - * requirements for a particular platform */ -#ifdef __SYMBIAN32__ -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# ifdef _WIN32 -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# endif -#else -# ifdef _WIN32 -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# else -# ifdef __OMX_EXPORTS -# define OMX_API -# else -# define OMX_API extern -# endif -# endif -#endif - -#ifndef OMX_APIENTRY -#define OMX_APIENTRY -#endif - -/** OMX_IN is used to identify inputs to an OMX function. This designation - will also be used in the case of a pointer that points to a parameter - that is used as an output. */ -#ifndef OMX_IN -#define OMX_IN -#endif - -/** OMX_OUT is used to identify outputs from an OMX function. This - designation will also be used in the case of a pointer that points - to a parameter that is used as an input. */ -#ifndef OMX_OUT -#define OMX_OUT -#endif - - -/** OMX_INOUT is used to identify parameters that may be either inputs or - outputs from an OMX function at the same time. This designation will - also be used in the case of a pointer that points to a parameter that - is used both as an input and an output. */ -#ifndef OMX_INOUT -#define OMX_INOUT -#endif - -/** OMX_ALL is used to as a wildcard to select all entities of the same type - * when specifying the index, or referring to a object by an index. (i.e. - * use OMX_ALL to indicate all N channels). When used as a port index - * for a config or parameter this OMX_ALL denotes that the config or - * parameter applies to the entire component not just one port. */ -#define OMX_ALL 0xFFFFFFFF - -/** In the following we define groups that help building doxygen documentation */ - -/** @defgroup core OpenMAX IL core - * Functions and structure related to the OMX IL core - */ - - /** @defgroup comp OpenMAX IL component - * Functions and structure related to the OMX IL component - */ - -/** @defgroup rpm Resource and Policy Management - * Structures for resource and policy management of components - */ - -/** @defgroup buf Buffer Management - * Buffer handling functions and structures - */ - -/** @defgroup tun Tunneling - * @ingroup core comp - * Structures and functions to manage tunnels among component ports - */ - -/** @defgroup cp Content Pipes - * @ingroup core - */ - - /** @defgroup metadata Metadata handling - * - */ - -/** OMX_U8 is an 8 bit unsigned quantity that is byte aligned */ -typedef unsigned char OMX_U8; - -/** OMX_S8 is an 8 bit signed quantity that is byte aligned */ -typedef signed char OMX_S8; - -/** OMX_U16 is a 16 bit unsigned quantity that is 16 bit word aligned */ -typedef unsigned short OMX_U16; - -/** OMX_S16 is a 16 bit signed quantity that is 16 bit word aligned */ -typedef signed short OMX_S16; - -/** OMX_U32 is a 32 bit unsigned quantity that is 32 bit word aligned */ -typedef unsigned int OMX_U32; - -/** OMX_S32 is a 32 bit signed quantity that is 32 bit word aligned */ -typedef signed int OMX_S32; - - -/* Users with compilers that cannot accept the "long long" designation should - define the OMX_SKIP64BIT macro. It should be noted that this may cause - some components to fail to compile if the component was written to require - 64 bit integral types. However, these components would NOT compile anyway - since the compiler does not support the way the component was written. -*/ -#ifndef OMX_SKIP64BIT -#ifdef __SYMBIAN32__ -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#elif defined(WIN32) - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned __int64 OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed __int64 OMX_S64; - -#else /* WIN32 */ - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#endif /* WIN32 */ -#endif - - -/** The OMX_BOOL type is intended to be used to represent a true or a false - value when passing parameters to and from the OMX core and components. The - OMX_BOOL is a 32 bit quantity and is aligned on a 32 bit word boundary. - */ -typedef enum OMX_BOOL { - OMX_FALSE = 0, - OMX_TRUE = !OMX_FALSE, - OMX_BOOL_MAX = 0x7FFFFFFF -} OMX_BOOL; - -#ifdef OMX_ANDROID_COMPILE_AS_32BIT_ON_64BIT_PLATFORMS - -typedef OMX_U32 OMX_PTR; -typedef OMX_PTR OMX_STRING; -typedef OMX_PTR OMX_BYTE; - -#else - -/** The OMX_PTR type is intended to be used to pass pointers between the OMX - applications and the OMX Core and components. This is a 32 bit pointer and - is aligned on a 32 bit boundary. - */ -typedef void* OMX_PTR; - -/** The OMX_STRING type is intended to be used to pass "C" type strings between - the application and the core and component. The OMX_STRING type is a 32 - bit pointer to a zero terminated string. The pointer is word aligned and - the string is byte aligned. - */ -typedef char* OMX_STRING; - -/** The OMX_BYTE type is intended to be used to pass arrays of bytes such as - buffers between the application and the component and core. The OMX_BYTE - type is a 32 bit pointer to a zero terminated string. The pointer is word - aligned and the string is byte aligned. - */ -typedef unsigned char* OMX_BYTE; - -/** OMX_UUIDTYPE is a very long unique identifier to uniquely identify - at runtime. This identifier should be generated by a component in a way - that guarantees that every instance of the identifier running on the system - is unique. */ - - -#endif - -typedef unsigned char OMX_UUIDTYPE[128]; - -/** The OMX_DIRTYPE enumeration is used to indicate if a port is an input or - an output port. This enumeration is common across all component types. - */ -typedef enum OMX_DIRTYPE -{ - OMX_DirInput, /**< Port is an input port */ - OMX_DirOutput, /**< Port is an output port */ - OMX_DirMax = 0x7FFFFFFF -} OMX_DIRTYPE; - -/** The OMX_ENDIANTYPE enumeration is used to indicate the bit ordering - for numerical data (i.e. big endian, or little endian). - */ -typedef enum OMX_ENDIANTYPE -{ - OMX_EndianBig, /**< big endian */ - OMX_EndianLittle, /**< little endian */ - OMX_EndianMax = 0x7FFFFFFF -} OMX_ENDIANTYPE; - - -/** The OMX_NUMERICALDATATYPE enumeration is used to indicate if data - is signed or unsigned - */ -typedef enum OMX_NUMERICALDATATYPE -{ - OMX_NumericalDataSigned, /**< signed data */ - OMX_NumericalDataUnsigned, /**< unsigned data */ - OMX_NumercialDataMax = 0x7FFFFFFF -} OMX_NUMERICALDATATYPE; - - -/** Unsigned bounded value type */ -typedef struct OMX_BU32 { - OMX_U32 nValue; /**< actual value */ - OMX_U32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_U32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BU32; - - -/** Signed bounded value type */ -typedef struct OMX_BS32 { - OMX_S32 nValue; /**< actual value */ - OMX_S32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_S32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BS32; - - -/** Structure representing some time or duration in microseconds. This structure - * must be interpreted as a signed 64 bit value. The quantity is signed to accommodate - * negative deltas and preroll scenarios. The quantity is represented in microseconds - * to accomodate high resolution timestamps (e.g. DVD presentation timestamps based - * on a 90kHz clock) and to allow more accurate and synchronized delivery (e.g. - * individual audio samples delivered at 192 kHz). The quantity is 64 bit to - * accommodate a large dynamic range (signed 32 bit values would allow only for plus - * or minus 35 minutes). - * - * Implementations with limited precision may convert the signed 64 bit value to - * a signed 32 bit value internally but risk loss of precision. - */ -#ifndef OMX_SKIP64BIT -typedef OMX_S64 OMX_TICKS; -#else -typedef struct OMX_TICKS -{ - OMX_U32 nLowPart; /** low bits of the signed 64 bit tick value */ - OMX_U32 nHighPart; /** high bits of the signed 64 bit tick value */ -} OMX_TICKS; -#endif -#define OMX_TICKS_PER_SECOND 1000000 - -/** Define the public interface for the OMX Handle. The core will not use - this value internally, but the application should only use this value. - */ -typedef void* OMX_HANDLETYPE; - -typedef struct OMX_MARKTYPE -{ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will - generate a mark event upon - processing the mark. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ -} OMX_MARKTYPE; - - -/** OMX_NATIVE_DEVICETYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the display - * or can be used by a audio port for native audio rendering */ -typedef void* OMX_NATIVE_DEVICETYPE; - -/** OMX_NATIVE_WINDOWTYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the window */ -typedef void* OMX_NATIVE_WINDOWTYPE; - -/** The OMX_VERSIONTYPE union is used to specify the version for - a structure or component. For a component, the version is entirely - specified by the component vendor. Components doing the same function - from different vendors may or may not have the same version. For - structures, the version shall be set by the entity that allocates the - structure. For structures specified in the OMX 1.1 specification, the - value of the version shall be set to 1.1.0.0 in all cases. Access to the - OMX_VERSIONTYPE can be by a single 32 bit access (e.g. by nVersion) or - by accessing one of the structure elements to, for example, check only - the Major revision. - */ -typedef union OMX_VERSIONTYPE -{ - struct - { - OMX_U8 nVersionMajor; /**< Major version accessor element */ - OMX_U8 nVersionMinor; /**< Minor version accessor element */ - OMX_U8 nRevision; /**< Revision version accessor element */ - OMX_U8 nStep; /**< Step version accessor element */ - } s; - OMX_U32 nVersion; /**< 32 bit value to make accessing the - version easily done in a single word - size copy/compare operation */ -} OMX_VERSIONTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/third_party/openmax/include/OMX_Video.h b/third_party/openmax/include/OMX_Video.h deleted file mode 100644 index 64dbe87b43..0000000000 --- a/third_party/openmax/include/OMX_Video.h +++ /dev/null @@ -1,1082 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_Video.h - OpenMax IL version 1.1.2 - * The structures is needed by Video components to exchange parameters - * and configuration data with OMX components. - */ -#ifndef OMX_Video_h -#define OMX_Video_h - -/** @defgroup video OpenMAX IL Video Domain - * @ingroup iv - * Structures for OpenMAX IL Video domain - * @{ - */ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/** - * Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration used to define the possible video compression codings. - * NOTE: This essentially refers to file extensions. If the coding is - * being used to specify the ENCODE type, then additional work - * must be done to configure the exact flavor of the compression - * to be used. For decode cases where the user application can - * not differentiate between MPEG-4 and H.264 bit streams, it is - * up to the codec to handle this. - */ -typedef enum OMX_VIDEO_CODINGTYPE { - OMX_VIDEO_CodingUnused, /**< Value when coding is N/A */ - OMX_VIDEO_CodingAutoDetect, /**< Autodetection of coding type */ - OMX_VIDEO_CodingMPEG2, /**< AKA: H.262 */ - OMX_VIDEO_CodingH263, /**< H.263 */ - OMX_VIDEO_CodingMPEG4, /**< MPEG-4 */ - OMX_VIDEO_CodingWMV, /**< all versions of Windows Media Video */ - OMX_VIDEO_CodingRV, /**< all versions of Real Video */ - OMX_VIDEO_CodingAVC, /**< H.264/AVC */ - OMX_VIDEO_CodingMJPEG, /**< Motion JPEG */ - OMX_VIDEO_CodingVP8, /**< Google VP8, formerly known as On2 VP8 */ - OMX_VIDEO_CodingVP9, /**< Google VP9 */ - OMX_VIDEO_CodingHEVC, /**< HEVC */ - OMX_VIDEO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_CodingMax = 0x7FFFFFFF -} OMX_VIDEO_CODINGTYPE; - - -/** - * Data structure used to define a video path. The number of Video paths for - * input and output will vary by type of the Video component. - * - * Input (aka Source) : zero Inputs, one Output, - * Splitter : one Input, 2 or more Outputs, - * Processing Element : one Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : one Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output video - * path. If additional vendor specific data is required, it should be - * transmitted to the component using the CustomCommand function. Compliant - * components will prepopulate this structure with optimal values during the - * GetDefaultInitParams command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nFrameHeight : Height of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nStride : Number of bytes per span of an image - * (i.e. indicates the number of bytes to get - * from span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * nBitrate : Bit rate of frame to be used on channel if - * compressed format is used. Use 0 for unknown, - * don't care or variable - * xFramerate : Frame rate to be used on channel if uncompressed - * format is used. Use 0 for unknown, don't care or - * variable. Units are Q16 frames per second. - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is - * specified, eColorFormat is used - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_VIDEO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_U32 nBitrate; - OMX_U32 xFramerate; - OMX_BOOL bFlagErrorConcealment; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_VIDEO_PORTDEFINITIONTYPE; - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is specified, - * eColorFormat is used - * eColorFormat : Decompressed format used by this component - * xFrameRate : Indicates the video frame rate in Q16 format - */ -typedef struct OMX_VIDEO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_U32 xFramerate; -} OMX_VIDEO_PARAM_PORTFORMATTYPE; - - -/** - * This is a structure for configuring video compression quantization - * parameter values. Codecs may support different QP values for different - * frame types. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nQpI : QP value to use for index frames - * nQpP : QP value to use for P frames - * nQpB : QP values to use for bidirectional frames - */ -typedef struct OMX_VIDEO_PARAM_QUANTIZATIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; -} OMX_VIDEO_PARAM_QUANTIZATIONTYPE; - - -/** - * Structure for configuration of video fast update parameters. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * bEnableVFU : Enable/Disable video fast update - * nFirstGOB : Specifies the number of the first macroblock row - * nFirstMB : specifies the first MB relative to the specified first GOB - * nNumMBs : Specifies the number of MBs to be refreshed from nFirstGOB - * and nFirstMB - */ -typedef struct OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableVFU; - OMX_U32 nFirstGOB; - OMX_U32 nFirstMB; - OMX_U32 nNumMBs; -} OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE; - - -/** - * Enumeration of possible bitrate control types - */ -typedef enum OMX_VIDEO_CONTROLRATETYPE { - OMX_Video_ControlRateDisable, - OMX_Video_ControlRateVariable, - OMX_Video_ControlRateConstant, - OMX_Video_ControlRateVariableSkipFrames, - OMX_Video_ControlRateConstantSkipFrames, - OMX_Video_ControlRateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_ControlRateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_ControlRateMax = 0x7FFFFFFF -} OMX_VIDEO_CONTROLRATETYPE; - - -/** - * Structure for configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * eControlRate : Control rate type enum - * nTargetBitrate : Target bitrate to encode with - */ -typedef struct OMX_VIDEO_PARAM_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_CONTROLRATETYPE eControlRate; - OMX_U32 nTargetBitrate; -} OMX_VIDEO_PARAM_BITRATETYPE; - - -/** - * Enumeration of possible motion vector (MV) types - */ -typedef enum OMX_VIDEO_MOTIONVECTORTYPE { - OMX_Video_MotionVectorPixel, - OMX_Video_MotionVectorHalfPel, - OMX_Video_MotionVectorQuarterPel, - OMX_Video_MotionVectorEighthPel, - OMX_Video_MotionVectorKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_MotionVectorVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_MotionVectorMax = 0x7FFFFFFF -} OMX_VIDEO_MOTIONVECTORTYPE; - - -/** - * Structure for configuring the number of motion vectors used as well - * as their accuracy. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : port that this structure applies to - * eAccuracy : Enumerated MV accuracy - * bUnrestrictedMVs : Allow unrestricted MVs - * bFourMV : Allow use of 4 MVs - * sXSearchRange : Search range in horizontal direction for MVs - * sYSearchRange : Search range in vertical direction for MVs - */ -typedef struct OMX_VIDEO_PARAM_MOTIONVECTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_MOTIONVECTORTYPE eAccuracy; - OMX_BOOL bUnrestrictedMVs; - OMX_BOOL bFourMV; - OMX_S32 sXSearchRange; - OMX_S32 sYSearchRange; -} OMX_VIDEO_PARAM_MOTIONVECTORTYPE; - - -/** - * Enumeration of possible methods to use for Intra Refresh - */ -typedef enum OMX_VIDEO_INTRAREFRESHTYPE { - OMX_VIDEO_IntraRefreshCyclic, - OMX_VIDEO_IntraRefreshAdaptive, - OMX_VIDEO_IntraRefreshBoth, - OMX_VIDEO_IntraRefreshKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_IntraRefreshVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_IntraRefreshRandom, - OMX_VIDEO_IntraRefreshMax = 0x7FFFFFFF -} OMX_VIDEO_INTRAREFRESHTYPE; - - -/** - * Structure for configuring intra refresh mode - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eRefreshMode : Cyclic, Adaptive, or Both - * nAirMBs : Number of intra macroblocks to refresh in a frame when - * AIR is enabled - * nAirRef : Number of times a motion marked macroblock has to be - * intra coded - * nCirMBs : Number of consecutive macroblocks to be coded as "intra" - * when CIR is enabled - */ -typedef struct OMX_VIDEO_PARAM_INTRAREFRESHTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_INTRAREFRESHTYPE eRefreshMode; - OMX_U32 nAirMBs; - OMX_U32 nAirRef; - OMX_U32 nCirMBs; -} OMX_VIDEO_PARAM_INTRAREFRESHTYPE; - - -/** - * Structure for enabling various error correction methods for video - * compression. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * bEnableHEC : Enable/disable header extension codes (HEC) - * bEnableResync : Enable/disable resynchronization markers - * nResynchMarkerSpacing : Resynch markers interval (in bits) to be - * applied in the stream - * bEnableDataPartitioning : Enable/disable data partitioning - * bEnableRVLC : Enable/disable reversible variable length - * coding - */ -typedef struct OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableHEC; - OMX_BOOL bEnableResync; - OMX_U32 nResynchMarkerSpacing; - OMX_BOOL bEnableDataPartitioning; - OMX_BOOL bEnableRVLC; -} OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE; - - -/** - * Configuration of variable block-size motion compensation (VBSMC) - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * b16x16 : Enable inter block search 16x16 - * b16x8 : Enable inter block search 16x8 - * b8x16 : Enable inter block search 8x16 - * b8x8 : Enable inter block search 8x8 - * b8x4 : Enable inter block search 8x4 - * b4x8 : Enable inter block search 4x8 - * b4x4 : Enable inter block search 4x4 - */ -typedef struct OMX_VIDEO_PARAM_VBSMCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL b16x16; - OMX_BOOL b16x8; - OMX_BOOL b8x16; - OMX_BOOL b8x8; - OMX_BOOL b8x4; - OMX_BOOL b4x8; - OMX_BOOL b4x4; -} OMX_VIDEO_PARAM_VBSMCTYPE; - - -/** - * H.263 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * Baseline : Baseline Profile: H.263 (V1), no optional modes - * H320 Coding : H.320 Coding Efficiency Backward Compatibility - * Profile: H.263+ (V2), includes annexes I, J, L.4 - * and T - * BackwardCompatible : Backward Compatibility Profile: H.263 (V1), - * includes annex F - * ISWV2 : Interactive Streaming Wireless Profile: H.263+ - * (V2), includes annexes I, J, K and T - * ISWV3 : Interactive Streaming Wireless Profile: H.263++ - * (V3), includes profile 3 and annexes V and W.6.3.8 - * HighCompression : Conversational High Compression Profile: H.263++ - * (V3), includes profiles 1 & 2 and annexes D and U - * Internet : Conversational Internet Profile: H.263++ (V3), - * includes profile 5 and annex K - * Interlace : Conversational Interlace Profile: H.263++ (V3), - * includes profile 5 and annex W.6.3.11 - * HighLatency : High Latency Profile: H.263++ (V3), includes - * profile 6 and annexes O.1 and P.5 - */ -typedef enum OMX_VIDEO_H263PROFILETYPE { - OMX_VIDEO_H263ProfileBaseline = 0x01, - OMX_VIDEO_H263ProfileH320Coding = 0x02, - OMX_VIDEO_H263ProfileBackwardCompatible = 0x04, - OMX_VIDEO_H263ProfileISWV2 = 0x08, - OMX_VIDEO_H263ProfileISWV3 = 0x10, - OMX_VIDEO_H263ProfileHighCompression = 0x20, - OMX_VIDEO_H263ProfileInternet = 0x40, - OMX_VIDEO_H263ProfileInterlace = 0x80, - OMX_VIDEO_H263ProfileHighLatency = 0x100, - OMX_VIDEO_H263ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_H263PROFILETYPE; - - -/** - * H.263 level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. - */ -typedef enum OMX_VIDEO_H263LEVELTYPE { - OMX_VIDEO_H263Level10 = 0x01, - OMX_VIDEO_H263Level20 = 0x02, - OMX_VIDEO_H263Level30 = 0x04, - OMX_VIDEO_H263Level40 = 0x08, - OMX_VIDEO_H263Level45 = 0x10, - OMX_VIDEO_H263Level50 = 0x20, - OMX_VIDEO_H263Level60 = 0x40, - OMX_VIDEO_H263Level70 = 0x80, - OMX_VIDEO_H263LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263LevelMax = 0x7FFFFFFF -} OMX_VIDEO_H263LEVELTYPE; - - -/** - * Specifies the picture type. These values should be OR'd to signal all - * pictures types which are allowed. - * - * ENUMS: - * Generic Picture Types: I, P and B - * H.263 Specific Picture Types: SI and SP - * H.264 Specific Picture Types: EI and EP - * MPEG-4 Specific Picture Types: S - */ -typedef enum OMX_VIDEO_PICTURETYPE { - OMX_VIDEO_PictureTypeI = 0x01, - OMX_VIDEO_PictureTypeP = 0x02, - OMX_VIDEO_PictureTypeB = 0x04, - OMX_VIDEO_PictureTypeSI = 0x08, - OMX_VIDEO_PictureTypeSP = 0x10, - OMX_VIDEO_PictureTypeEI = 0x11, - OMX_VIDEO_PictureTypeEP = 0x12, - OMX_VIDEO_PictureTypeS = 0x14, - OMX_VIDEO_PictureTypeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_PictureTypeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_PictureTypeMax = 0x7FFFFFFF -} OMX_VIDEO_PICTURETYPE; - - -/** - * H.263 Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : H.263 profile(s) to use - * eLevel : H.263 level(s) to use - * bPLUSPTYPEAllowed : Indicating that it is allowed to use PLUSPTYPE - * (specified in the 1998 version of H.263) to - * indicate custom picture sizes or clock - * frequencies - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bForceRoundingTypeToZero : value of the RTYPE bit (bit 6 of MPPTYPE) is - * not constrained. It is recommended to change - * the value of the RTYPE bit for each reference - * picture in error-free communication - * nPictureHeaderRepetition : Specifies the frequency of picture header - * repetition - * nGOBHeaderInterval : Specifies the interval of non-empty GOB - * headers in units of GOBs - */ -typedef struct OMX_VIDEO_PARAM_H263TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_H263PROFILETYPE eProfile; - OMX_VIDEO_H263LEVELTYPE eLevel; - OMX_BOOL bPLUSPTYPEAllowed; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bForceRoundingTypeToZero; - OMX_U32 nPictureHeaderRepetition; - OMX_U32 nGOBHeaderInterval; -} OMX_VIDEO_PARAM_H263TYPE; - - -/** - * MPEG-2 profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_MPEG2PROFILETYPE { - OMX_VIDEO_MPEG2ProfileSimple = 0, /**< Simple Profile */ - OMX_VIDEO_MPEG2ProfileMain, /**< Main Profile */ - OMX_VIDEO_MPEG2Profile422, /**< 4:2:2 Profile */ - OMX_VIDEO_MPEG2ProfileSNR, /**< SNR Profile */ - OMX_VIDEO_MPEG2ProfileSpatial, /**< Spatial Profile */ - OMX_VIDEO_MPEG2ProfileHigh, /**< High Profile */ - OMX_VIDEO_MPEG2ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2PROFILETYPE; - - -/** - * MPEG-2 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG2LEVELTYPE { - OMX_VIDEO_MPEG2LevelLL = 0, /**< Low Level */ - OMX_VIDEO_MPEG2LevelML, /**< Main Level */ - OMX_VIDEO_MPEG2LevelH14, /**< High 1440 */ - OMX_VIDEO_MPEG2LevelHL, /**< High Level */ - OMX_VIDEO_MPEG2LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2LEVELTYPE; - - -/** - * MPEG-2 params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : MPEG-2 profile(s) to use - * eLevel : MPEG-2 levels(s) to use - */ -typedef struct OMX_VIDEO_PARAM_MPEG2TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_MPEG2PROFILETYPE eProfile; - OMX_VIDEO_MPEG2LEVELTYPE eLevel; -} OMX_VIDEO_PARAM_MPEG2TYPE; - - -/** - * MPEG-4 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * - Simple Profile, Levels 1-3 - * - Simple Scalable Profile, Levels 1-2 - * - Core Profile, Levels 1-2 - * - Main Profile, Levels 2-4 - * - N-bit Profile, Level 2 - * - Scalable Texture Profile, Level 1 - * - Simple Face Animation Profile, Levels 1-2 - * - Simple Face and Body Animation (FBA) Profile, Levels 1-2 - * - Basic Animated Texture Profile, Levels 1-2 - * - Hybrid Profile, Levels 1-2 - * - Advanced Real Time Simple Profiles, Levels 1-4 - * - Core Scalable Profile, Levels 1-3 - * - Advanced Coding Efficiency Profile, Levels 1-4 - * - Advanced Core Profile, Levels 1-2 - * - Advanced Scalable Texture, Levels 2-3 - */ -typedef enum OMX_VIDEO_MPEG4PROFILETYPE { - OMX_VIDEO_MPEG4ProfileSimple = 0x01, - OMX_VIDEO_MPEG4ProfileSimpleScalable = 0x02, - OMX_VIDEO_MPEG4ProfileCore = 0x04, - OMX_VIDEO_MPEG4ProfileMain = 0x08, - OMX_VIDEO_MPEG4ProfileNbit = 0x10, - OMX_VIDEO_MPEG4ProfileScalableTexture = 0x20, - OMX_VIDEO_MPEG4ProfileSimpleFace = 0x40, - OMX_VIDEO_MPEG4ProfileSimpleFBA = 0x80, - OMX_VIDEO_MPEG4ProfileBasicAnimated = 0x100, - OMX_VIDEO_MPEG4ProfileHybrid = 0x200, - OMX_VIDEO_MPEG4ProfileAdvancedRealTime = 0x400, - OMX_VIDEO_MPEG4ProfileCoreScalable = 0x800, - OMX_VIDEO_MPEG4ProfileAdvancedCoding = 0x1000, - OMX_VIDEO_MPEG4ProfileAdvancedCore = 0x2000, - OMX_VIDEO_MPEG4ProfileAdvancedScalable = 0x4000, - OMX_VIDEO_MPEG4ProfileAdvancedSimple = 0x8000, - OMX_VIDEO_MPEG4ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4PROFILETYPE; - - -/** - * MPEG-4 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG4LEVELTYPE { - OMX_VIDEO_MPEG4Level0 = 0x01, /**< Level 0 */ - OMX_VIDEO_MPEG4Level0b = 0x02, /**< Level 0b */ - OMX_VIDEO_MPEG4Level1 = 0x04, /**< Level 1 */ - OMX_VIDEO_MPEG4Level2 = 0x08, /**< Level 2 */ - OMX_VIDEO_MPEG4Level3 = 0x10, /**< Level 3 */ - OMX_VIDEO_MPEG4Level4 = 0x20, /**< Level 4 */ - OMX_VIDEO_MPEG4Level4a = 0x40, /**< Level 4a */ - OMX_VIDEO_MPEG4Level5 = 0x80, /**< Level 5 */ - OMX_VIDEO_MPEG4LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4LEVELTYPE; - - -/** - * MPEG-4 configuration. This structure handles configuration options - * which are specific to MPEG4 algorithms - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header (H263+ - * Annex K). Put zero if not used - * bSVH : Enable Short Video Header mode - * bGov : Flag to enable GOV - * nPFrames : Number of P frames between each I frame (also called - * GOV period) - * nBFrames : Number of B frames between each I frame - * nIDCVLCThreshold : Value of intra DC VLC threshold - * bACPred : Flag to use ac prediction - * nMaxPacketSize : Maximum size of packet in bytes. - * nTimeIncRes : Used to pass VOP time increment resolution for MPEG4. - * Interpreted as described in MPEG4 standard. - * eProfile : MPEG-4 profile(s) to use. - * eLevel : MPEG-4 level(s) to use. - * nAllowedPictureTypes : Specifies the picture types allowed in the bitstream - * nHeaderExtension : Specifies the number of consecutive video packet - * headers within a VOP - * bReversibleVLC : Specifies whether reversible variable length coding - * is in use - */ -typedef struct OMX_VIDEO_PARAM_MPEG4TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_BOOL bSVH; - OMX_BOOL bGov; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_U32 nIDCVLCThreshold; - OMX_BOOL bACPred; - OMX_U32 nMaxPacketSize; - OMX_U32 nTimeIncRes; - OMX_VIDEO_MPEG4PROFILETYPE eProfile; - OMX_VIDEO_MPEG4LEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_U32 nHeaderExtension; - OMX_BOOL bReversibleVLC; -} OMX_VIDEO_PARAM_MPEG4TYPE; - - -/** - * WMV Versions - */ -typedef enum OMX_VIDEO_WMVFORMATTYPE { - OMX_VIDEO_WMVFormatUnused = 0x01, /**< Format unused or unknown */ - OMX_VIDEO_WMVFormat7 = 0x02, /**< Windows Media Video format 7 */ - OMX_VIDEO_WMVFormat8 = 0x04, /**< Windows Media Video format 8 */ - OMX_VIDEO_WMVFormat9 = 0x08, /**< Windows Media Video format 9 */ - OMX_VIDEO_WMFFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_WMFFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_WMVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_WMVFORMATTYPE; - - -/** - * WMV Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of WMV stream / data - */ -typedef struct OMX_VIDEO_PARAM_WMVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_WMVFORMATTYPE eFormat; -} OMX_VIDEO_PARAM_WMVTYPE; - - -/** - * Real Video Version - */ -typedef enum OMX_VIDEO_RVFORMATTYPE { - OMX_VIDEO_RVFormatUnused = 0, /**< Format unused or unknown */ - OMX_VIDEO_RVFormat8, /**< Real Video format 8 */ - OMX_VIDEO_RVFormat9, /**< Real Video format 9 */ - OMX_VIDEO_RVFormatG2, /**< Real Video Format G2 */ - OMX_VIDEO_RVFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_RVFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_RVFORMATTYPE; - - -/** - * Real Video Params - * - * STUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of RV stream / data - * nBitsPerPixel : Bits per pixel coded in the frame - * nPaddedWidth : Padded width in pixel of a video frame - * nPaddedHeight : Padded Height in pixels of a video frame - * nFrameRate : Rate of video in frames per second - * nBitstreamFlags : Flags which internal information about the bitstream - * nBitstreamVersion : Bitstream version - * nMaxEncodeFrameSize: Max encoded frame size - * bEnablePostFilter : Turn on/off post filter - * bEnableTemporalInterpolation : Turn on/off temporal interpolation - * bEnableLatencyMode : When enabled, the decoder does not display a decoded - * frame until it has detected that no enhancement layer - * frames or dependent B frames will be coming. This - * detection usually occurs when a subsequent non-B - * frame is encountered - */ -typedef struct OMX_VIDEO_PARAM_RVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_RVFORMATTYPE eFormat; - OMX_U16 nBitsPerPixel; - OMX_U16 nPaddedWidth; - OMX_U16 nPaddedHeight; - OMX_U32 nFrameRate; - OMX_U32 nBitstreamFlags; - OMX_U32 nBitstreamVersion; - OMX_U32 nMaxEncodeFrameSize; - OMX_BOOL bEnablePostFilter; - OMX_BOOL bEnableTemporalInterpolation; - OMX_BOOL bEnableLatencyMode; -} OMX_VIDEO_PARAM_RVTYPE; - - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_AVCPROFILETYPE { - OMX_VIDEO_AVCProfileBaseline = 0x01, /**< Baseline profile */ - OMX_VIDEO_AVCProfileMain = 0x02, /**< Main profile */ - OMX_VIDEO_AVCProfileExtended = 0x04, /**< Extended profile */ - OMX_VIDEO_AVCProfileHigh = 0x08, /**< High profile */ - OMX_VIDEO_AVCProfileHigh10 = 0x10, /**< High 10 profile */ - OMX_VIDEO_AVCProfileHigh422 = 0x20, /**< High 4:2:2 profile */ - OMX_VIDEO_AVCProfileHigh444 = 0x40, /**< High 4:4:4 profile */ - OMX_VIDEO_AVCProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_AVCPROFILETYPE; - - -/** - * AVC level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_AVCLEVELTYPE { - OMX_VIDEO_AVCLevel1 = 0x01, /**< Level 1 */ - OMX_VIDEO_AVCLevel1b = 0x02, /**< Level 1b */ - OMX_VIDEO_AVCLevel11 = 0x04, /**< Level 1.1 */ - OMX_VIDEO_AVCLevel12 = 0x08, /**< Level 1.2 */ - OMX_VIDEO_AVCLevel13 = 0x10, /**< Level 1.3 */ - OMX_VIDEO_AVCLevel2 = 0x20, /**< Level 2 */ - OMX_VIDEO_AVCLevel21 = 0x40, /**< Level 2.1 */ - OMX_VIDEO_AVCLevel22 = 0x80, /**< Level 2.2 */ - OMX_VIDEO_AVCLevel3 = 0x100, /**< Level 3 */ - OMX_VIDEO_AVCLevel31 = 0x200, /**< Level 3.1 */ - OMX_VIDEO_AVCLevel32 = 0x400, /**< Level 3.2 */ - OMX_VIDEO_AVCLevel4 = 0x800, /**< Level 4 */ - OMX_VIDEO_AVCLevel41 = 0x1000, /**< Level 4.1 */ - OMX_VIDEO_AVCLevel42 = 0x2000, /**< Level 4.2 */ - OMX_VIDEO_AVCLevel5 = 0x4000, /**< Level 5 */ - OMX_VIDEO_AVCLevel51 = 0x8000, /**< Level 5.1 */ - OMX_VIDEO_AVCLevel52 = 0x10000, /**< Level 5.2 */ - OMX_VIDEO_AVCLevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLEVELTYPE; - - -/** - * AVC loop filter modes - * - * OMX_VIDEO_AVCLoopFilterEnable : Enable - * OMX_VIDEO_AVCLoopFilterDisable : Disable - * OMX_VIDEO_AVCLoopFilterDisableSliceBoundary : Disabled on slice boundaries - */ -typedef enum OMX_VIDEO_AVCLOOPFILTERTYPE { - OMX_VIDEO_AVCLoopFilterEnable = 0, - OMX_VIDEO_AVCLoopFilterDisable, - OMX_VIDEO_AVCLoopFilterDisableSliceBoundary, - OMX_VIDEO_AVCLoopFilterKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLoopFilterVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLoopFilterMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLOOPFILTERTYPE; - - -/** - * AVC params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header, put - * zero if not used - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * bUseHadamard : Enable/disable Hadamard transform - * nRefFrames : Max number of reference frames to use for inter - * motion search (1-16) - * nRefIdxTrailing : Pic param set ref frame index (index into ref - * frame buffer of trailing frames list), B frame - * support - * nRefIdxForward : Pic param set ref frame index (index into ref - * frame buffer of forward frames list), B frame - * support - * bEnableUEP : Enable/disable unequal error protection. This - * is only valid of data partitioning is enabled. - * bEnableFMO : Enable/disable flexible macroblock ordering - * bEnableASO : Enable/disable arbitrary slice ordering - * bEnableRS : Enable/disable sending of redundant slices - * eProfile : AVC profile(s) to use - * eLevel : AVC level(s) to use - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bFrameMBsOnly : specifies that every coded picture of the - * coded video sequence is a coded frame - * containing only frame macroblocks - * bMBAFF : Enable/disable switching between frame and - * field macroblocks within a picture - * bEntropyCodingCABAC : Entropy decoding method to be applied for the - * syntax elements for which two descriptors appear - * in the syntax tables - * bWeightedPPrediction : Enable/disable weighted prediction shall not - * be applied to P and SP slices - * nWeightedBipredicitonMode : Default weighted prediction is applied to B - * slices - * bconstIpred : Enable/disable intra prediction - * bDirect8x8Inference : Specifies the method used in the derivation - * process for luma motion vectors for B_Skip, - * B_Direct_16x16 and B_Direct_8x8 as specified - * in subclause 8.4.1.2 of the AVC spec - * bDirectSpatialTemporal : Flag indicating spatial or temporal direct - * mode used in B slice coding (related to - * bDirect8x8Inference) . Spatial direct mode is - * more common and should be the default. - * nCabacInitIdx : Index used to init CABAC contexts - * eLoopFilterMode : Enable/disable loop filter - */ -typedef struct OMX_VIDEO_PARAM_AVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_BOOL bUseHadamard; - OMX_U32 nRefFrames; - OMX_U32 nRefIdx10ActiveMinus1; - OMX_U32 nRefIdx11ActiveMinus1; - OMX_BOOL bEnableUEP; - OMX_BOOL bEnableFMO; - OMX_BOOL bEnableASO; - OMX_BOOL bEnableRS; - OMX_VIDEO_AVCPROFILETYPE eProfile; - OMX_VIDEO_AVCLEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bFrameMBsOnly; - OMX_BOOL bMBAFF; - OMX_BOOL bEntropyCodingCABAC; - OMX_BOOL bWeightedPPrediction; - OMX_U32 nWeightedBipredicitonMode; - OMX_BOOL bconstIpred ; - OMX_BOOL bDirect8x8Inference; - OMX_BOOL bDirectSpatialTemporal; - OMX_U32 nCabacInitIdc; - OMX_VIDEO_AVCLOOPFILTERTYPE eLoopFilterMode; -} OMX_VIDEO_PARAM_AVCTYPE; - -typedef struct OMX_VIDEO_PARAM_PROFILELEVELTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 eProfile; /**< type is OMX_VIDEO_AVCPROFILETYPE, OMX_VIDEO_H263PROFILETYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 eLevel; /**< type is OMX_VIDEO_AVCLEVELTYPE, OMX_VIDEO_H263LEVELTYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 nProfileIndex; /**< Used to query for individual profile support information, - This parameter is valid only for - OMX_IndexParamVideoProfileLevelQuerySupported index, - For all other indices this parameter is to be ignored. */ -} OMX_VIDEO_PARAM_PROFILELEVELTYPE; - -/** - * Structure for dynamically configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * nEncodeBitrate : Target average bitrate to be generated in bps - */ -typedef struct OMX_VIDEO_CONFIG_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEncodeBitrate; -} OMX_VIDEO_CONFIG_BITRATETYPE; - -/** - * Defines Encoder Frame Rate setting - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * xEncodeFramerate : Encoding framerate represented in Q16 format - */ -typedef struct OMX_CONFIG_FRAMERATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 xEncodeFramerate; /* Q16 format */ -} OMX_CONFIG_FRAMERATETYPE; - -typedef struct OMX_CONFIG_INTRAREFRESHVOPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL IntraRefreshVOP; -} OMX_CONFIG_INTRAREFRESHVOPTYPE; - -typedef struct OMX_CONFIG_MACROBLOCKERRORMAPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nErrMapSize; /* Size of the Error Map in bytes */ - OMX_U8 ErrMap[1]; /* Error map hint */ -} OMX_CONFIG_MACROBLOCKERRORMAPTYPE; - -typedef struct OMX_CONFIG_MBERRORREPORTINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; -} OMX_CONFIG_MBERRORREPORTINGTYPE; - -typedef struct OMX_PARAM_MACROBLOCKSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nMacroblocks; -} OMX_PARAM_MACROBLOCKSTYPE; - -/** - * AVC Slice Mode modes - * - * OMX_VIDEO_SLICEMODE_AVCDefault : Normal frame encoding, one slice per frame - * OMX_VIDEO_SLICEMODE_AVCMBSlice : NAL mode, number of MBs per frame - * OMX_VIDEO_SLICEMODE_AVCByteSlice : NAL mode, number of bytes per frame - */ -typedef enum OMX_VIDEO_AVCSLICEMODETYPE { - OMX_VIDEO_SLICEMODE_AVCDefault = 0, - OMX_VIDEO_SLICEMODE_AVCMBSlice, - OMX_VIDEO_SLICEMODE_AVCByteSlice, - OMX_VIDEO_SLICEMODE_AVCKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_SLICEMODE_AVCVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_SLICEMODE_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCSLICEMODETYPE; - -/** - * AVC FMO Slice Mode Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNumSliceGroups : Specifies the number of slice groups - * nSliceGroupMapType : Specifies the type of slice groups - * eSliceMode : Specifies the type of slice - */ -typedef struct OMX_VIDEO_PARAM_AVCSLICEFMO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U8 nNumSliceGroups; - OMX_U8 nSliceGroupMapType; - OMX_VIDEO_AVCSLICEMODETYPE eSliceMode; -} OMX_VIDEO_PARAM_AVCSLICEFMO; - -/** - * AVC IDR Period Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nIDRPeriod : Specifies periodicity of IDR frames - * nPFrames : Specifies internal of coding Intra frames - */ -typedef struct OMX_VIDEO_CONFIG_AVCINTRAPERIOD { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIDRPeriod; - OMX_U32 nPFrames; -} OMX_VIDEO_CONFIG_AVCINTRAPERIOD; - -/** - * AVC NAL Size Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNaluBytes : Specifies the NAL unit size - */ -typedef struct OMX_VIDEO_CONFIG_NALSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNaluBytes; -} OMX_VIDEO_CONFIG_NALSIZE; - - -/** - * Deinterlace Config - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nEnable : Specifies to enable deinterlace - */ -typedef struct OMX_VIDEO_CONFIG_DEINTERLACE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEnable; -} OMX_VIDEO_CONFIG_DEINTERLACE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/third_party/openmax/include/OMX_VideoExt.h b/third_party/openmax/include/OMX_VideoExt.h deleted file mode 100644 index 5bf6fd4878..0000000000 --- a/third_party/openmax/include/OMX_VideoExt.h +++ /dev/null @@ -1,166 +0,0 @@ -/* - * Copyright (c) 2010 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_VideoExt.h - OpenMax IL version 1.1.2 - * The OMX_VideoExt header file contains extensions to the - * definitions used by both the application and the component to - * access video items. - */ - -#ifndef OMX_VideoExt_h -#define OMX_VideoExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - -/** NALU Formats */ -typedef enum OMX_NALUFORMATSTYPE { - OMX_NaluFormatStartCodes = 1, - OMX_NaluFormatOneNaluPerBuffer = 2, - OMX_NaluFormatOneByteInterleaveLength = 4, - OMX_NaluFormatTwoByteInterleaveLength = 8, - OMX_NaluFormatFourByteInterleaveLength = 16, - OMX_NaluFormatCodingMax = 0x7FFFFFFF -} OMX_NALUFORMATSTYPE; - -/** NAL Stream Format */ -typedef struct OMX_NALSTREAMFORMATTYPE{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_NALUFORMATSTYPE eNaluFormat; -} OMX_NALSTREAMFORMATTYPE; - -/** VP8 profiles */ -typedef enum OMX_VIDEO_VP8PROFILETYPE { - OMX_VIDEO_VP8ProfileMain = 0x01, - OMX_VIDEO_VP8ProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_VP8PROFILETYPE; - -/** VP8 levels */ -typedef enum OMX_VIDEO_VP8LEVELTYPE { - OMX_VIDEO_VP8Level_Version0 = 0x01, - OMX_VIDEO_VP8Level_Version1 = 0x02, - OMX_VIDEO_VP8Level_Version2 = 0x04, - OMX_VIDEO_VP8Level_Version3 = 0x08, - OMX_VIDEO_VP8LevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8LevelMax = 0x7FFFFFFF -} OMX_VIDEO_VP8LEVELTYPE; - -/** VP8 Param */ -typedef struct OMX_VIDEO_PARAM_VP8TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_VP8PROFILETYPE eProfile; - OMX_VIDEO_VP8LEVELTYPE eLevel; - OMX_U32 nDCTPartitions; - OMX_BOOL bErrorResilientMode; -} OMX_VIDEO_PARAM_VP8TYPE; - -/** Structure for configuring VP8 reference frames */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bPreviousFrameRefresh; - OMX_BOOL bGoldenFrameRefresh; - OMX_BOOL bAlternateFrameRefresh; - OMX_BOOL bUsePreviousFrame; - OMX_BOOL bUseGoldenFrame; - OMX_BOOL bUseAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMETYPE; - -/** Structure for querying VP8 reference frame type */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bIsIntraFrame; - OMX_BOOL bIsGoldenOrAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE; - -/** HEVC Profiles */ -typedef enum OMX_VIDEO_HEVCPROFILETYPE { - OMX_VIDEO_HEVCProfileMain = 0x01, - OMX_VIDEO_HEVCProfileMain10 = 0x02, - OMX_VIDEO_HEVCProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCPROFILETYPE; - -/** HEVC levels */ -typedef enum OMX_VIDEO_HEVCLEVELTYPE { - OMX_VIDEO_HEVCLevel_Version0 = 0x0, - OMX_VIDEO_HEVCMainTierLevel1 = 0x1, - OMX_VIDEO_HEVCHighTierLevel1 = 0x2, - OMX_VIDEO_HEVCMainTierLevel2 = 0x4, - OMX_VIDEO_HEVCHighTierLevel2 = 0x8, - OMX_VIDEO_HEVCMainTierLevel21 = 0x10, - OMX_VIDEO_HEVCHighTierLevel21 = 0x20, - OMX_VIDEO_HEVCMainTierLevel3 = 0x40, - OMX_VIDEO_HEVCHighTierLevel3 = 0x80, - OMX_VIDEO_HEVCMainTierLevel31 = 0x100, - OMX_VIDEO_HEVCHighTierLevel31 = 0x200, - OMX_VIDEO_HEVCMainTierLevel4 = 0x400, - OMX_VIDEO_HEVCHighTierLevel4 = 0x800, - OMX_VIDEO_HEVCMainTierLevel41 = 0x1000, - OMX_VIDEO_HEVCHighTierLevel41 = 0x2000, - OMX_VIDEO_HEVCMainTierLevel5 = 0x4000, - OMX_VIDEO_HEVCHighTierLevel5 = 0x8000, - OMX_VIDEO_HEVCMainTierLevel51 = 0x10000, - OMX_VIDEO_HEVCHighTierLevel51 = 0x20000, - OMX_VIDEO_HEVCMainTierLevel52 = 0x40000, - OMX_VIDEO_HEVCHighTierLevel52 = 0x80000, - OMX_VIDEO_HEVCMainTierLevel6 = 0x100000, - OMX_VIDEO_HEVCHighTierLevel6 = 0x200000, - OMX_VIDEO_HEVCMainTierLevel61 = 0x400000, - OMX_VIDEO_HEVCHighTierLevel61 = 0x800000, - OMX_VIDEO_HEVCMainTierLevel62 = 0x1000000, - OMX_VIDEO_HEVCLevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCLEVELTYPE; - -/** HEVC Param */ -typedef struct OMX_VIDEO_PARAM_HEVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_HEVCPROFILETYPE eProfile; - OMX_VIDEO_HEVCLEVELTYPE eLevel; -} OMX_VIDEO_PARAM_HEVCTYPE; - - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_VideoExt_h */ -/* File EOF */ diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py index 040c2e18f0..67bc1ffb7b 100755 --- a/tools/camerastream/compressed_vipc.py +++ b/tools/camerastream/compressed_vipc.py @@ -11,10 +11,7 @@ V4L2_BUF_FLAG_KEYFRAME = 8 def writer(fn, addr, sock_name): import cereal.messaging as messaging - HEADER = b"\x00\x00\x00\x01\x40\x01\x0c\x01\xff\xff\x01\x60\x00\x00\x03\x00\xb0\x00\x00\x03\x00\x00\x03\x00\x96\xac\x09\x00\x00\x00\x01\x42\x01\x01\x01\x60\x00\x00\x03\x00\xb0\x00\x00\x03\x00\x00\x03\x00\x96\xa0\x03\xd0\x80\x13\x07\x1b\x2e\x5a\xee\x4c\x92\xea\x00\xbb\x42\x84\xa0\x00\x00\x00\x01\x44\x01\xc0\xe2\x4f\x09\xc1\x80\xc6\x08\x40\x00" fifo_file = open(fn, "wb") - fifo_file.write(HEADER) - fifo_file.flush() os.environ["ZMQ"] = "1" messaging.context = messaging.Context() @@ -26,23 +23,25 @@ def writer(fn, addr, sock_name): msgs = messaging.drain_sock(sock, wait_for_one=True) for evt in msgs: evta = getattr(evt, evt.which()) - lat = ((evt.logMonoTime/1e9) - (evta.timestampEof/1e6))*1000 - print("%2d %4d %.3f %.3f latency %.2f ms" % (len(msgs), evta.idx, evt.logMonoTime/1e9, evta.timestampEof/1e6, lat), len(evta.data), sock_name) - if evta.idx != 0 and evta.idx != (last_idx+1): + lat = ((evt.logMonoTime/1e9) - (evta.idx.timestampEof/1e9))*1000 + print("%2d %4d %.3f %.3f latency %.2f ms" % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, lat), len(evta.data), sock_name) + if evta.idx.encodeId != 0 and evta.idx.encodeId != (last_idx+1): print("DROP!") - last_idx = evta.idx - if evta.flags & V4L2_BUF_FLAG_KEYFRAME or evta.flags == 0x7f001030: + last_idx = evta.idx.encodeId + if evta.idx.flags & V4L2_BUF_FLAG_KEYFRAME: + fifo_file.write(evta.header) seen_iframe = True if not seen_iframe: print("waiting for iframe") continue fifo_file.write(evta.data) - fifo_file.flush() + +FFMPEG_OPTIONS = {"probesize": "32", "flags": "low_delay"} def decoder_nvidia(fn, vipc_server, vst, yuv=True, rgb=False): sys.path.append("/raid.dell2/PyNvCodec") import PyNvCodec as nvc # pylint: disable=import-error - decoder = nvc.PyNvDecoder(fn, 0, {"probesize": "32"}) + decoder = nvc.PyNvDecoder(fn, 0, FFMPEG_OPTIONS) cc1 = nvc.ColorspaceConversionContext(nvc.ColorSpace.BT_709, nvc.ColorRange.JPEG) if rgb: @@ -72,7 +71,7 @@ def decoder_nvidia(fn, vipc_server, vst, yuv=True, rgb=False): def decoder_ffmpeg(fn, vipc_server, vst, yuv=True, rgb=False): import av # pylint: disable=import-error - container = av.open(fn, options={"probesize": "32"}) + container = av.open(fn, options=FFMPEG_OPTIONS) cnt = 0 for frame in container.decode(video=0): if rgb: @@ -87,6 +86,7 @@ import argparse if __name__ == "__main__": parser = argparse.ArgumentParser(description='Decode video streams and broacast on VisionIPC') parser.add_argument("addr", help="Address of comma 3") + parser.add_argument('--pipes', action='store_true', help='Only create pipes') parser.add_argument('--nvidia', action='store_true', help='Use nvidia instead of ffmpeg') parser.add_argument('--rgb', action='store_true', help='Also broadcast RGB') parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") @@ -112,7 +112,9 @@ if __name__ == "__main__": os.unlink(FIFO_NAME) os.mkfifo(FIFO_NAME) multiprocessing.Process(target=writer, args=(FIFO_NAME, sys.argv[1], k)).start() - if args.nvidia: + if args.pipes: + print("connect to", FIFO_NAME) + elif args.nvidia: multiprocessing.Process(target=decoder_nvidia, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start() else: multiprocessing.Process(target=decoder_ffmpeg, args=(FIFO_NAME, vipc_server, v, True, args.rgb)).start()