fast-screen-capture2.cpp
Go to the documentation of this file.
00001 #if (ANDROID_VER < 420)
00002     #error must define ANDROID_VER >= 420
00003 #endif
00004 #include <unistd.h>
00005 #include <sys/types.h>
00006 #include <fcntl.h>
00007 #include <linux/fb.h>
00008 #include <stdio.h>
00009 #include <stdlib.h>
00010 #include <stdarg.h>
00011 #include <errno.h>
00012 #include <sys/ioctl.h>
00013 #include <sys/mman.h>
00014 #include <math.h>
00015 #include <err.h>
00016 #include <stdbool.h>
00017 #include <sys/time.h>
00018 #include <time.h>
00019 #include <signal.h>
00020 #include <pthread.h>
00021 #include "libcutils.h"
00022 #include "libgui.h"
00023 #include "libui.h"
00024 #include "libskia.h"
00025 #include "libstagefright.h"
00026 #if MAKE_STD==1
00027     #include <new>
00028 #endif
00029 
00030 using namespace android;
00031 
00032 struct ASC_PRIV_DATA;
00033 struct ASC {
00034     ASC_PRIV_DATA* priv_data;
00035     char* data;
00036     int size;
00037     int w; //short size
00038     int h; //long size
00039     char pixfmtName[32];
00040 };
00041 
00042 #define LOG(fmt, arg...)         ({static bool __logged=false; if (needLog||!__logged){_LOG("%s" fmt "%s", needLog?"":"--------rare case--------", ##arg, needLog?"":"\n\n");__logged=true;}})
00043 #define LOGI(fmt, arg...)        LOG("--------" fmt "\n\n", ##arg)
00044 #define ABORT(fmt, arg...)       ({_LOG(fmt ". Now exit", ##arg); exit(0);})
00045 #define ABORT_ERRNO(fmt, arg...) ({_LOG(fmt " [errno %d(%s)] Now exit", errno, strerror(errno), ##arg); exit(0);})
00046 
00047 static void _LOG(const char* format, ...) {
00048     char buf[4096];
00049     int cnt;
00050     va_list va;
00051     struct timespec ct;
00052     struct tm * st;
00053     clock_gettime(CLOCK_REALTIME, &ct);
00054     st = localtime(&ct.tv_sec);
00055     cnt = sprintf(buf, "%02d/%02d %02d:%02d:%02d.%03d [ASC %d] ", st->tm_mon+1, st->tm_mday, st->tm_hour, st->tm_min, st->tm_sec, (int)(ct.tv_nsec/1000000), gettid());
00056     va_start(va, format);
00057     cnt += vsnprintf(buf+cnt, sizeof(buf)-cnt, format, va);
00058     va_end(va);
00059     if (cnt > sizeof(buf)) cnt = sizeof(buf); else if (cnt <= 0) {cnt = 7; strcpy(buf, "LogErr");};
00060     if (buf[cnt-1]==0) cnt--; //always true
00061     if (buf[cnt-1]!='\n') buf[cnt++] = '\n';
00062     write(STDERR_FILENO, buf, cnt);
00063 }
00064 
00065 #undef ENABLE_RESEND
00066 #if (ANDROID_VER<440)
00067     #define ENABLE_RESEND 1
00068 #endif
00069 
00070 #if ENABLE_RESEND 
00071     static struct timespec lastTime = {0};
00072     // #define SEND_AFTER_NS  ((int)(0.005*1000000000))
00073     #define SEND_AFTER_NS  0
00074     #define RESEND_AFTER_NS ((int)(1000000000*0.25-SEND_AFTER_NS))
00075 #endif
00076 
00077 #define toEvenInt(n) ((int)(ceil(((float)(n))/2)*2))
00078 #define min(a,b) ((a) < (b) ? (a) : (b))
00079 #define max(a,b) ((a) > (b) ? (a) : (b))
00080 
00081 static bool isFirstTime = true;
00082 static bool needLog = true;
00083 static Mutex mutex;
00084 static Condition cond;
00085 static sp<IBinder> __csBinder;
00086 // static sp<ISurfaceComposer> __cs;
00087 static sp<IBinder> mainDisp, virtDisp;
00088 static DisplayInfo mainDispInfo;
00089 static int capture_w, capture_h, logicalFrameSize;
00090 class MyGraphicBufferProducer;
00091 static MyGraphicBufferProducer* bp;
00092 static bool alwaysRotate = false;
00093 // static Vector<ComposerState> _emptyComposerStates; //dummy
00094 // static Vector<DisplayState > _displayStates;
00095 // static DisplayState* virtDispState = NULL;
00096 static DisplayState* virtDispState = new DisplayState();
00097 static int TRANS_ID_GET_DISPLAY_INFO = 0;
00098 static int TRANS_ID_SET_DISPLAY_STATE = 0;
00099 
00100 static Vector<sp<ABuffer> > ibfs;
00101 
00102 #define BPP 4
00103 
00104 #if MAKE_STD==1
00105     static sp<MediaCodec> codec;
00106 #endif
00107 
00108 struct CallbackStep {
00109     int ind;
00110     const char* name;
00111 };
00112 static CallbackStep bpSteps[1/*invalid step 0*/+32] = {0};
00113 static int bpStepMax = 0;
00114 
00115 
00116 
00117 typedef void* VADDR;
00118 typedef VADDR* PVTBL;
00119 #define PVTBL_OF(inst) (*((PVTBL*)(inst)))
00120 #define getVirtFuncIndex(f) _getVirtFuncIndex(0, f)
00121 static int _getVirtFuncIndex(int dummy, ...) {
00122     int i;
00123     va_list va;
00124     va_start(va, dummy);
00125     i = va_arg(va, int);
00126     va_end(va);
00127     return i/sizeof(VADDR);
00128 }
00129 
00130 #define INIT_NEXT_CALLBACK_STEP(virtFuncName) ({ \
00131     if (++bpStepMax >= sizeof(bpSteps)/sizeof(bpSteps[0])-1) ABORT("too many bpSteps"); \
00132     bpSteps[bpStepMax].ind = getVirtFuncIndex(&IGraphicBufferProducer::virtFuncName); \
00133     bpSteps[bpStepMax].name = #virtFuncName; \
00134 })
00135 
00136 static void bpInitCallbackSteps() {
00137     LOG("bpics");
00138     INIT_NEXT_CALLBACK_STEP(query);
00139     INIT_NEXT_CALLBACK_STEP(connect);
00140     #if (ANDROID_VER<440)
00141         INIT_NEXT_CALLBACK_STEP(setSynchronousMode);
00142     #endif
00143     INIT_NEXT_CALLBACK_STEP(dequeueBuffer);
00144     INIT_NEXT_CALLBACK_STEP(requestBuffer);
00145     INIT_NEXT_CALLBACK_STEP(queueBuffer);
00146 }
00147 
00148 static int bpCodeToVirtIndex(uint32_t code) {
00149     static int diff = -1;
00150     if (diff == -1)
00151         diff = getVirtFuncIndex(&IGraphicBufferProducer::requestBuffer)-1/*code*/;
00152     if (diff <= 0) ABORT("bad rbf vi");
00153     return code + diff;
00154 }
00155 
00156 static int convertOrient(int orient) {
00157     return !alwaysRotate ? orient : orient==0 ? 1 : orient==1 ? 0 : orient==2 ? 3 : orient==3 ? 2 : 4;
00158 }
00159 
00160 #if (ANDROID_VER>=500)
00161     #define MIN_DISP_INFO_HEAD 2*sizeof(int)  //vector head
00162 #else
00163     #define MIN_DISP_INFO_HEAD 0
00164 #endif
00165 #define MIN_DISP_INFO_SIZE  (MIN_DISP_INFO_HEAD + ((size_t)&(((DisplayInfo*)NULL)->reserved)))
00166 
00167 static int getOrient() {
00168     LOG("r go");
00169     // status_t err = __cs->getDisplayInfo(mainDisp, &mainDispInfo);
00170 
00171     Parcel data, reply;
00172     data.writeInterfaceToken(ISurfaceComposer::descriptor);
00173     data.writeStrongBinder(mainDisp);
00174     status_t err = __csBinder->transact(TRANS_ID_GET_DISPLAY_INFO, data, &reply);
00175     if (err) ABORT("r go e %d", err);
00176     if (reply.dataSize() < MIN_DISP_INFO_SIZE) ABORT("r go s t l");
00177     DisplayInfo* info = (DisplayInfo*)(reply.data() + MIN_DISP_INFO_HEAD);
00178     LOG("r go o %d", info->orientation);
00179     return info->orientation;
00180 }
00181 
00182 static void setVirtDispOrient(int orient) {
00183     virtDispState->what = DisplayState::eDisplayProjectionChanged;
00184     virtDispState->orientation = convertOrient(orient);
00185     LOGI("r sds o %d mo %d", virtDispState->orientation, orient);
00186     //Although specified No wait, but android 4.2 still cause wait max 5 seconds, so do not use ISurfaceComposer nor SurfaceComposerClient
00187     // status_t err = __cs->setTransactionState(_emptyComposerStates, _displayStates, 0);
00188 
00189     Parcel data;
00190     data.writeInterfaceToken(ISurfaceComposer::descriptor);
00191     data.writeInt32(0);
00192     data.writeInt32(1);
00193     virtDispState->write(data);
00194     data.writeInt32(0/*flags*/);
00195     status_t err = __csBinder->transact(TRANS_ID_SET_DISPLAY_STATE, data, NULL, 1/*TF_ONE_WAY*/);
00196 
00197     if (err) ABORT("r sds e %d", err);
00198     LOG(".r sds");
00199 }
00200 
00201 struct MyGraphicBufferProducer : public BnGraphicBufferProducer {
00202     int mWidth;
00203     int mHeight;
00204     volatile int mInUsing;
00205     bool mIsGBufferRequested;
00206     sp<Fence> mFence;
00207     PixelFormat mFormat;
00208     GraphicBuffer* mGBuf;
00209     int mGBufUsage;
00210     char* mGBufData;
00211     int mInternalWidth;
00212     bool mHaveData;
00213     int mConsumerUsage;
00214     int64_t mSeq;
00215 
00216     MyGraphicBufferProducer(int w, int h) : BnGraphicBufferProducer() {
00217         LOG("bp c w %d h %d", w, h);
00218         mWidth = w;
00219         mHeight = h;
00220         mInUsing = 0;
00221         mIsGBufferRequested = false;
00222         mGBuf = NULL;
00223         mGBufData = NULL;
00224         mHaveData = false;
00225         mFence = Fence::NO_FENCE;
00226         mFormat = HAL_PIXEL_FORMAT_RGBA_8888;
00227         mConsumerUsage = GRALLOC_USAGE_SW_READ_OFTEN;
00228         mSeq = 0;
00229     }
00230 
00231     virtual ~MyGraphicBufferProducer() {
00232         LOG("bp d");
00233         delete mGBuf;
00234     }
00235 
00236     virtual status_t requestBuffer(int slot, sp<GraphicBuffer>* buf) {
00237         LOG("rbf %d", slot);
00238         if (slot != 0) ABORT("rbf %d n 0", slot);
00239         if (mGBuf == NULL) ABORT("rbf bg n");
00240         *buf = mGBuf;
00241         mIsGBufferRequested = true;
00242         return 0;
00243     }
00244 
00245     virtual status_t setBufferCount(int bufferCount) {
00246         if (bufferCount==1) LOG("sbc %d", bufferCount);
00247         else ABORT("sbc %d", bufferCount);
00248         return 0;
00249     }
00250 
00251     #if (ANDROID_VER>=440)
00252         virtual status_t dequeueBuffer(int *slot, sp<Fence>* fence, bool async, uint32_t w, uint32_t h, uint32_t format, uint32_t usage)
00253     #elif (ANDROID_VER>=430)
00254         virtual status_t dequeueBuffer(int *slot, sp<Fence>* fence, uint32_t w, uint32_t h, uint32_t format, uint32_t usage)
00255     #elif (ANDROID_VER>=420)
00256         virtual status_t dequeueBuffer(int *slot, sp<Fence>& fence, uint32_t w, uint32_t h, uint32_t format, uint32_t usage)
00257     #endif
00258     {
00259         #if (ANDROID_VER>=440)
00260             LOG("d w %d h %d f %d u 0x%x a %d", w, h, format, usage, async);
00261         #elif (ANDROID_VER>=420)
00262             LOG("d w %d h %d f %d u 0x%x", w, h, format, usage);
00263         #endif
00264         if (w != mWidth || h != mHeight) LOG("d w h abn");
00265 
00266         if (mGBuf==NULL) {
00267             if (format!=1 && format!=5) ABORT("f %d u", format);
00268             mFormat = format;
00269             int bpp = bytesPerPixel(format);
00270             if (bpp != BPP) ABORT("bpp %d u", bpp);
00271 
00272             mGBufUsage = (usage&~GRALLOC_USAGE_SW_READ_MASK)|mConsumerUsage;
00273 
00274             LOG("cr gb");
00275             mGBuf = new GraphicBuffer(mWidth, mHeight, mFormat, mGBufUsage);
00276             if (mGBuf==NULL) ABORT("n gb e");
00277             LOG("gb %p", mGBuf);
00278 
00279             LOG("g nb");
00280             ANativeWindowBuffer* nb = mGBuf->getNativeBuffer();
00281             LOGI("g nb r %p w %d h %d f %d s %d h %p", nb, nb->width, nb->height, nb->format, nb->stride, nb->handle);
00282             mInternalWidth = nb->stride;
00283 
00284             LOG("l gb");
00285             status_t err = mGBuf->lock(mConsumerUsage, (void**)&mGBufData);
00286             if (err || !mGBufData) ABORT("l gb e %d", err);
00287             LOG("l gb p %p", mGBufData);
00288         }
00289         else if (format != mFormat)  ABORT("d f %d n %d", format, mFormat);
00290 
00291         *slot = 0;
00292         #if (ANDROID_VER>=430)
00293             *fence = mFence; //set NULL cause android crash!!
00294         #elif (ANDROID_VER>=420)
00295             fence = mFence;
00296         #endif
00297         return mIsGBufferRequested ? 0 : IGraphicBufferProducer::BUFFER_NEEDS_REALLOCATION;
00298     }
00299 
00300     virtual status_t queueBuffer(int slot, const QueueBufferInput& input, QueueBufferOutput* output) {
00301         LOG("q %d i %p o %p sq %lld", slot, &input, output, ++mSeq);
00302         LOG("_q f.p %p cr %d %d %d %d sm %d tr %d", input.fence.get(), input.crop.left, input.crop.top, input.crop.right, input.crop.bottom, input.scalingMode, input.transform);
00303         LOG("_q f.f %d", input.fence==NULL?-1:input.fence->getFd());
00304         if (slot != 0) ABORT("q %d n 0", slot);
00305         if (output) {
00306             output->width = mWidth;
00307             output->height = mHeight;
00308             output->transformHint = 0;
00309             output->numPendingBuffers = 0;
00310         }
00311 
00312         int orient = getOrient();
00313 
00314         AutoMutex autoLock(mutex);
00315         mFence = input.fence;
00316 
00317         if (convertOrient(orient) != virtDispState->orientation) {
00318             setVirtDispOrient(orient);
00319             #if ENABLE_RESEND
00320                 if(lastTime.tv_sec) cond.signal(); //wake up resend thread
00321             #endif
00322         } else {
00323             mHaveData = true;
00324             #if ENABLE_RESEND
00325                 clock_gettime(CLOCK_MONOTONIC, &lastTime);
00326             #endif
00327             cond.signal(); //anyway wake up main or resend thread
00328         }
00329         return 0;
00330     }
00331 
00332     #if (ANDROID_VER>=440)
00333         virtual void cancelBuffer(int slot, const sp<Fence>& fence)
00334     #elif (ANDROID_VER>=420)
00335         virtual void cancelBuffer(int slot, sp<Fence> fence)
00336     #endif
00337     {
00338         LOG("cb %d", slot);
00339     }
00340 
00341     virtual int query(int what, int* value) { //what is defined in window.h
00342         int err = 0;
00343         switch(what) {
00344         case NATIVE_WINDOW_WIDTH:
00345         case NATIVE_WINDOW_DEFAULT_WIDTH:
00346             LOG("qr w");
00347             *value = mWidth;
00348             break;
00349         case NATIVE_WINDOW_HEIGHT:
00350         case NATIVE_WINDOW_DEFAULT_HEIGHT:
00351             LOG("qr h");
00352             *value = mHeight;
00353             break;
00354         case NATIVE_WINDOW_FORMAT:
00355             LOG("qr f");
00356             *value = mFormat;
00357             break;
00358         case NATIVE_WINDOW_CONSUMER_USAGE_BITS:
00359             LOG("qr cu");
00360             *value = mConsumerUsage;
00361             break;
00362         case NATIVE_WINDOW_MIN_UNDEQUEUED_BUFFERS:
00363             LOG("qr mub");
00364             *value = 0;
00365             break;
00366         case NATIVE_WINDOW_TRANSFORM_HINT:
00367             LOG("qr th");
00368             *value = 0;
00369             break;
00370         case NATIVE_WINDOW_QUEUES_TO_WINDOW_COMPOSER:
00371             LOG("qr qwc");
00372             *value = 0;
00373             break;
00374         case NATIVE_WINDOW_CONCRETE_TYPE:
00375             LOG("qr ct");
00376             *value = 0;
00377             break;
00378         default:
00379             LOG("qr %d", what);
00380             err = -EINVAL;
00381         }
00382         return err;
00383     }
00384 
00385     #if (ANDROID_VER<440)
00386     virtual status_t setSynchronousMode(bool enabled) {
00387         LOG("m %d", enabled);
00388         return 0;
00389     }
00390     #endif
00391 
00392     #if (ANDROID_VER>=440)
00393         virtual status_t connect(const sp<IBinder>& token, int api, bool producerControlledByApp, QueueBufferOutput* output)
00394     #elif (ANDROID_VER>=420)
00395         virtual status_t connect(int api, QueueBufferOutput* output)
00396     #endif
00397     {
00398         LOG("c %d %p", api, output);
00399         if (output) {
00400             output->width = mWidth;
00401             output->height = mHeight;
00402             output->transformHint = 0;
00403             output->numPendingBuffers = 0;
00404         }
00405         return 0;
00406     }
00407 
00408     virtual status_t disconnect(int api) {
00409         LOG("dc");
00410     }
00411 
00412     #if (ANDROID_VER>=500)
00413         virtual status_t detachBuffer(int slot) {LOG("dtb %d", slot); return -EINVAL;}
00414         virtual status_t detachNextBuffer(sp<GraphicBuffer>* outBuffer, sp<Fence>* outFence) {LOG("dtnb"); return -EINVAL;};
00415         virtual status_t attachBuffer(int* outSlot, const sp<GraphicBuffer>& buffer) {LOG("atb"); return -EINVAL;};
00416         virtual status_t setSidebandStream(/*const sp<NativeHandle>&*/void* stream) {LOG("ssbs"); return -EINVAL;};
00417         virtual void allocateBuffers(bool async, uint32_t width, uint32_t height, uint32_t format, uint32_t usage) {LOG("atb");};
00418     #endif
00419 
00420     virtual status_t onTransact(uint32_t code, const Parcel& data, Parcel* reply, uint32_t flags = 0) {
00421         LOG("t %d ds %d", code, data.dataSize());
00422         #if 1 //(ANDROID_VER==420)
00423             // analyse time sequence, determin each code
00424             static int bpStepOfCode[32] = {0/*invalid step*/};
00425             if (code > 0 && code < sizeof(bpStepOfCode)/sizeof(bpStepOfCode[0])) {
00426                 if (!bpStepOfCode[code]) { //every code will be handled once
00427                     static int step = 0;
00428                     if(++step <= bpStepMax) {
00429                         LOGI("rg %d st%d", code, step);
00430                         bpStepOfCode[code] = step;
00431 
00432                         int ind = bpCodeToVirtIndex(code);
00433                         if (ind != bpSteps[step].ind) {
00434                             LOG("n rd");
00435                             AutoMutex autoLock(mutex);
00436                             static PVTBL old_vtbl = NULL;
00437                             if (!old_vtbl) {
00438                                 LOG("pr pt");
00439                                 old_vtbl = PVTBL_OF(this);
00440                                 // for(int i=-ghostCnt; i<normalCnt; i++) LOG("vtbl[%d]:%p", i, old_vtbl[i]);
00441                                 enum{ ghostCnt = 16, normalCnt=64};
00442                                 static VADDR new_vtbl[ghostCnt+normalCnt] = {0};
00443                                 memcpy(new_vtbl, old_vtbl-ghostCnt, sizeof(new_vtbl));
00444                                 LOG("pt vt %p %p", old_vtbl, new_vtbl + ghostCnt);
00445                                 PVTBL_OF(this) = new_vtbl + ghostCnt;
00446                             }
00447 
00448                             LOG("rd %p %p i%d i%d", PVTBL_OF(this)[ind], old_vtbl[bpSteps[step].ind], ind, bpSteps[step].ind);
00449                             PVTBL_OF(this)[ind] = old_vtbl[bpSteps[step].ind];
00450                             LOG(".rd");
00451                         }
00452                     } else {
00453                         ABORT("t m b");
00454                     }
00455                 }
00456             } else {
00457                 LOG("ig c");
00458                 code = -1;
00459             }
00460         #endif
00461         status_t err = BnGraphicBufferProducer::onTransact(code, data, reply, flags);
00462         LOG(".t %d r %d", code, err);
00463         return err;
00464     }
00465 };
00466 
00467 static uint32_t sniffered_transact_code = 0;
00468 
00469 void sniffTransact(IBinder* binder) {
00470     static VADDR old_addr = NULL;
00471     static VADDR sniffer_addr = NULL;
00472     static VADDR* p_cur_addr = NULL;
00473 
00474     struct TransactSniffer {
00475         virtual status_t transact(uint32_t code, const Parcel& data, Parcel* reply, uint32_t flags) {
00476             LOGI("sn tr c %d", code);
00477             sniffered_transact_code = code;
00478             LOG("st sn");
00479             *p_cur_addr = old_addr;
00480             status_t err = ((IBinder*)this)->transact(code, data, reply, flags);
00481             if (reply) {
00482                 LOG("rp %p %d %d", reply->data(), reply->dataSize(), reply->dataPosition());
00483                 int len = reply->dataSize();
00484                 for(int i = 0; i < len/sizeof(void*); i++) {
00485                     LOG("_rp %p", ((void**)reply->data())[i]);
00486                 }
00487             }
00488             return err;
00489         }
00490     };
00491 
00492     if (!p_cur_addr) {
00493         LOG("pr pt");
00494         PVTBL old_vtbl = PVTBL_OF(binder);
00495         // for(int i=-ghostCnt; i<normalCnt; i++) LOG("vtbl[%d]:%p", i, old_vtbl[i]);
00496         enum{ ghostCnt = 8, normalCnt=64};
00497         static VADDR new_vtbl[ghostCnt+normalCnt] = {0};
00498         memcpy(new_vtbl, old_vtbl-ghostCnt, sizeof(new_vtbl));
00499         LOG("pt vt %p %p", old_vtbl, new_vtbl + ghostCnt);
00500         PVTBL_OF(binder) = new_vtbl + ghostCnt;
00501 
00502         int ind = getVirtFuncIndex(&IBinder::transact);
00503         if (ind >= normalCnt || ind <= 0) ABORT("b t vi");
00504         old_addr = old_vtbl[ind];
00505         if (!old_addr) ABORT("b t a");
00506 
00507         TransactSniffer sniffer;
00508         sniffer_addr = PVTBL_OF(&sniffer)[0];
00509         if (!sniffer_addr) ABORT("b s a");
00510 
00511         p_cur_addr = &PVTBL_OF(binder)[ind];
00512     }
00513 
00514     LOG("s sn");
00515     *p_cur_addr = sniffer_addr;
00516 }
00517 
00518 #if MAKE_TRIAL==1
00519 static void chkDev() {
00520     #if (ANDROID_VER>=400)
00521         char key1[128] =  {0};
00522         char key2[128] =  {0};
00523         char m[256] = {0};
00524         char v[256] = {0};
00525         char m1[32] = {0};
00526         char m2[32] = {0};
00527         char v1[32] = {0};
00528         char v2[32] = {0};
00529         int i=0;
00530         key1[i++] = 'r'; key1[i++] = 'o'; key1[i++] = '.'; key1[i++] = 'p'; key1[i++] = 'r'; key1[i++] = 'o'; key1[i++] = 'd'; key1[i++] = 'u'; key1[i++] = 'c'; key1[i++] = 't'; key1[i++] = '.'; key1[i++] = 'm'; key1[i++] = 'o'; key1[i++] = 'd'; key1[i++] = 'e'; key1[i++] = 'l'; 
00531         i=0;
00532         key2[i++] = 'r'; key2[i++] = 'o'; key2[i++] = '.'; key2[i++] = 'b'; key2[i++] = 'u'; key2[i++] = 'i'; key2[i++] = 'l'; key2[i++] = 'd'; key2[i++] = '.'; key2[i++] = 'v'; key2[i++] = 'e'; key2[i++] = 'r'; key2[i++] = 's'; key2[i++] = 'i'; key2[i++] = 'o'; key2[i++] = 'n'; key2[i++] = '.'; key2[i++] = 'r'; key2[i++] = 'e'; key2[i++] = 'l'; key2[i++] = 'e'; key2[i++] = 'a'; key2[i++] = 's'; key2[i++] = 'e';
00533         i=0;
00534         m1[i++] = 'M'; m1[i++] = 'D'; m1[i++] = '-'; m1[i++] = '1'; m1[i++] = '0'; m1[i++] = '0'; m1[i++] = '8'; m1[i++] = 'B';
00535         i=0;
00536         v1[i++] = '4'; v1[i++] = '.'; v1[i++] = '2'; v1[i++] = '.'; v1[i++] = '2';
00537         i=0;
00538         m2[i++] = 'M'; m2[i++] = 'I'; m2[i++] = ' '; m2[i++] = 'P'; m2[i++] = 'A'; m2[i++] = 'D';
00539         i=0;
00540         v2[i++] = '4'; v2[i++] = '.'; v2[i++] = '2'; v2[i++] = '.'; v2[i++] = '4';
00541         property_get(key1, m, "");        LOG("[%s]", m);
00542         property_get(key2, v, "");        LOG("[%s]", v);
00543         if(0==strcmp(m, m1) && 0==strcmp(v, v1)) return;
00544         if(0==strcmp(m, m2) && 0==strcmp(v, v2)) return;
00545         ABORT("t m");
00546     #endif
00547 }
00548 #endif
00549 
00550 static void asc_init(ASC* asc) {
00551     status_t err;
00552     #if MAKE_TRIAL==1
00553         if (time(NULL) >= 1416466615) ABORT("!");
00554         chkDev();
00555     #endif
00556     LOG("p %d", getpid());
00557 
00558     bpInitCallbackSteps();
00559 
00560     #if (ANDROID_VER>=430)
00561         //force loader fails in android 4.3, otherwise can not differ it with 4.4
00562         if (getpid()==-1) {
00563             sp<IBinder> tmp;
00564             SurfaceComposerClient::destroyDisplay(tmp);
00565         }
00566     #endif
00567     #if (ANDROID_VER>=500)
00568         //force loader fails in android 4.4, otherwise can not differ it with 5.0
00569         if (getpid()==-1) {
00570             ScreenshotClient s;
00571             sp<IBinder> d;
00572             status_t err = s.update(d, Rect(), 0, 0, false);
00573         }
00574     #endif
00575 
00576     LOG("stp");
00577     ProcessState::self()->startThreadPool();
00578 
00579     LOG("gs");
00580     __csBinder = defaultServiceManager()->getService(String16("SurfaceFlinger"));
00581     // __cs = ISurfaceComposer::asInterface(__csBinder);
00582 
00583     LOG("gbd");
00584     mainDisp = SurfaceComposerClient::getBuiltInDisplay(0 /*1 is hdmi*/);
00585     if (mainDisp.get()==NULL) ABORT("gbd e");
00586     LOG("bd %p", mainDisp.get());
00587 
00588     sniffTransact(__csBinder);
00589 
00590     LOG("gd");
00591     err = SurfaceComposerClient::getDisplayInfo(mainDisp, &mainDispInfo);
00592     if (err) ABORT("gdi e %d", err);
00593     LOG("gd w %d h %d o %d", mainDispInfo.w, mainDispInfo.h, mainDispInfo.orientation);
00594 
00595     TRANS_ID_GET_DISPLAY_INFO = sniffered_transact_code;
00596 
00597     LOG("r gd");
00598     //some device use strange head file which put ISurfaceComposer::getMainDisplayInfo after getBuiltInDisplay so vptr index changed, so test here
00599     // err = __cs->getDisplayInfo(mainDisp, &mainDispInfo);
00600     {
00601         Parcel data, reply;
00602         data.writeInterfaceToken(ISurfaceComposer::descriptor);
00603         data.writeStrongBinder(mainDisp);
00604         err = __csBinder->transact(TRANS_ID_GET_DISPLAY_INFO, data, &reply);
00605         if (err) ABORT("r gd abn");
00606         if (reply.dataSize() < MIN_DISP_INFO_SIZE) ABORT("r gd s t l");
00607         DisplayInfo* info = (DisplayInfo*)(reply.data() + MIN_DISP_INFO_HEAD);
00608         if (info->w != mainDispInfo.w || info->h != mainDispInfo.h) ABORT("r gd abn. w %d h %d", info->w, info->h);
00609         mainDispInfo.orientation = info->orientation;
00610     }
00611     LOG(".r gd w %d h %d o %d", mainDispInfo.w, mainDispInfo.h, mainDispInfo.orientation);
00612 
00613     //sample mainDispInfo: {w:720, h:1280}
00614 
00615     LOG("o c r w %d h %d", asc->w, asc->h);
00616     if (!asc->w && !asc->h) {  //normal case
00617         capture_w = mainDispInfo.w;
00618         capture_h = mainDispInfo.h;
00619     } else if (asc->w && !asc->h) {
00620         capture_w = toEvenInt(asc->w);
00621         capture_h = toEvenInt(asc->w*mainDispInfo.h/mainDispInfo.w);
00622     } else if (asc->h && !asc->w) {
00623         capture_h = toEvenInt(asc->h);
00624         capture_w = toEvenInt(asc->h*mainDispInfo.w/mainDispInfo.h);
00625     } else { //asc->w && asc->h
00626         capture_w = toEvenInt(asc->w);
00627         capture_h = toEvenInt(asc->h);
00628     }
00629     logicalFrameSize = capture_w*capture_h*BPP;
00630     alwaysRotate = (mainDispInfo.w < mainDispInfo.h) != (capture_w < capture_h);
00631     LOG("c c r w %d h %d ar %d", capture_w, capture_h, alwaysRotate);
00632 }
00633 
00634 static void asc_create_virtual_display() {
00635     status_t err;
00636     Rect mainViewPort, virtViewPort;
00637     mainViewPort.right = mainViewPort.bottom = max(mainDispInfo.w, mainDispInfo.h);
00638     virtViewPort.right = virtViewPort.bottom = max(capture_w, capture_h);
00639 
00640     LOG("cd");
00641     virtDisp = SurfaceComposerClient::createDisplay(String8("QJASC"), true /*secure*/);
00642     if (virtDisp.get()==NULL) ABORT("cd e");
00643 
00644     bp = new MyGraphicBufferProducer(capture_w, capture_h);
00645 
00646     LOG("pr ds");
00647     SurfaceComposerClient::openGlobalTransaction();
00648     SurfaceComposerClient::setDisplaySurface(virtDisp, NULL);
00649     SurfaceComposerClient::setDisplayProjection(virtDisp, 0, /*layerStackRect:*/mainViewPort, /*displayRect:*/virtViewPort);
00650     SurfaceComposerClient::setDisplayLayerStack(virtDisp, 0);
00651 
00652     sniffTransact(__csBinder);
00653 
00654     LOG("t sds");
00655     SurfaceComposerClient::closeGlobalTransaction();
00656 
00657     TRANS_ID_SET_DISPLAY_STATE = sniffered_transact_code;
00658 
00659     LOG("pr r ds");
00660     // _displayStates.add();
00661     // virtDispState = _displayStates.editArray();
00662     virtDispState->what = DisplayState::eSurfaceChanged|DisplayState::eLayerStackChanged|DisplayState::eDisplayProjectionChanged;
00663     virtDispState->token = virtDisp;
00664     virtDispState->surface = bp;
00665     virtDispState->orientation = convertOrient(mainDispInfo.orientation);
00666     virtDispState->viewport = mainViewPort;
00667     virtDispState->frame = virtViewPort;
00668     virtDispState->layerStack = 0;
00669     LOG("r sds o %d mo %d", virtDispState->orientation, mainDispInfo.orientation);
00670     // __cs->setTransactionState(_emptyComposerStates, _displayStates, 0);
00671     {
00672         Parcel data;
00673         data.writeInterfaceToken(ISurfaceComposer::descriptor);
00674         data.writeInt32(0);
00675         data.writeInt32(1);
00676         virtDispState->write(data);
00677         data.writeInt32(0/*flags*/);
00678         status_t err = __csBinder->transact(TRANS_ID_SET_DISPLAY_STATE, data, NULL, 1/*TF_ONE_WAY*/);
00679         if (err) ABORT("r sds e %d", err);
00680     }
00681 }
00682 
00683 extern "C" void asc_capture(ASC* asc) {
00684     status_t err;
00685     AutoMutex autoLock(mutex);
00686     static int64_t seq = 0;
00687 
00688     if (isFirstTime) {
00689         asc_init(asc);
00690         asc_create_virtual_display();
00691     }
00692 
00693     #if ENABLE_RESEND
00694         if (!bp->mHaveData && !isFirstTime && lastTime.tv_sec) { //if there are data need be resent
00695             if ((lastTime.tv_nsec += RESEND_AFTER_NS) >= 1000000000) {
00696                 lastTime.tv_nsec -= 1000000000;
00697                 lastTime.tv_sec++;
00698             }
00699             LOG("dl mx %d ms 4 ru d", RESEND_AFTER_NS/1000000);
00700             if ((err=cond.waitAbsMono(mutex, &lastTime)) && err != -ETIMEDOUT) {
00701                 LOG("w err:%d", err);
00702             }
00703             if (!bp->mHaveData) {
00704                 LOGI("rt pr d sq %lld  t c c...", seq);
00705                 lastTime.tv_sec = 0;
00706                 return;
00707             }
00708         }
00709     #endif
00710 
00711     while ( !bp->mHaveData ) {
00712         LOG("w 4 d");
00713         cond.wait(mutex);
00714     }
00715     LOG("g n d e");
00716     bp->mHaveData = false;
00717 
00718     if (bp->mFence && bp->mFence->isValid()) {
00719          LOG("w 4 f");
00720          bp->mFence->wait(-1);
00721     }
00722 
00723     if (isFirstTime) {
00724         asc->w = bp->mInternalWidth;
00725         asc->h = bp->mHeight;
00726         strcpy(asc->pixfmtName, bp->mFormat==1?"rgb0":"bgr0");
00727         asc->size = bp->mInternalWidth*bp->mHeight*BPP;
00728         asc->data = bp->mGBufData;
00729     }
00730     
00731     seq++;
00732     LOG("r d sq:%lld t c c...", seq);
00733 
00734     if (isFirstTime) {
00735         if (! (getenv("ASC_LOG_ALL") && atoi(getenv("ASC_LOG_ALL")) > 0) )
00736             needLog = false;
00737         isFirstTime = false;
00738     }
00739 }
00740 
00741 #if MAKE_TEST==1
00742     extern "C" int main(int argc, char** argv) {
00743         ASC asc;
00744         memset(&asc, 0, sizeof(ASC));
00745         asc.w = argc>1 && atoi(argv[1])> 0 ? atoi(argv[1]) : 0;
00746         asc.h = argc>2 && atoi(argv[2])> 0 ? atoi(argv[2]) : 0;
00747 
00748         for(;;) {
00749             asc_capture(&asc);
00750             static int64_t seq = 0;
00751             LOGI("o i %lld", ++seq);
00752             write(1, asc.data, asc.size);
00753             #if 0
00754                 LOG("encode to jpeg");
00755                 SkData* streamData;
00756                 {
00757                     SkBitmap b;
00758                     if (!b.setConfig(SkBitmap::kARGB_8888_Config, mWidth, mHeight, mInternalWidth*BPP)) ABORT("failed to setConfig");
00759                     b.setPixels(mGBufData);
00760                     SkDynamicMemoryWStream stream;
00761                     if (!SkImageEncoder::EncodeStream(&stream, b, SkImageEncoder::kJPEG_Type, 100)) ABORT("failed to encode to jpeg");
00762                     LOG("get jpeg");
00763                     streamData = stream.copyToData();
00764                     write(1/*stdout*/, streamData->p, streamData->size);
00765                 }
00766                 delete streamData;
00767             #endif
00768         }
00769     }
00770 #endif
00771 
00772 #if MAKE_STD==1
00773     static void* thread_feed_input(void* thd_param) {
00774         for(;;) {
00775             status_t err;
00776             AutoMutex autoLock(mutex);
00777             static int64_t seq = 0;
00778 
00779 
00780             LOG("codec->dequeueInputBuffer")
00781             int ibfs_index;
00782             err = codec->dequeueInputBuffer(&ibfs_index);
00783             if (err) ABORT('codec->dequeueInputBuffer err %d', err);
00784 
00785 
00786             while ( !bp->mHaveData ) {
00787                 LOG("w 4 d");
00788                 cond.wait(mutex);
00789             }
00790             LOG("g n d e");
00791             bp->mHaveData = false;
00792 
00793             if (bp->mFence && bp->mFence->isValid()) {
00794                  LOG("w 4 f");
00795                  bp->mFence->wait(-1);
00796             }
00797 
00798             LOG("copy data to codec input buf")
00799             if (bp->mInternalWidth==bp->mWidth) {
00800                 memcpy(ibfs->get(ibfs_index)->base(), mGBufData, logicalFrameSize);
00801             } else {
00802                 char* p1 = ibfs.get(ibfs_index)->base();
00803                 char* p2 = bp->mGBufData;
00804                 int size1 = bp->mWidth*BPP;
00805                 int size2 = bp->mInternalWidth*BPP;
00806                 for (int h=0; h < height; h++, p2 += size2, p1+= size1)
00807                     memmove(p1, p2, size1);
00808             }
00809 
00810             LOG("codec->queueInputBuffer")
00811             err = codec->queueInputBuffer(slot, 0, logicalFrameSize, ALooper::GetNowUs(), 0);
00812             if (err) ABORT("codec->queueInputBuffer err %d", err);
00813 
00814             seq++;
00815             LOG("r d sq:%lld t c c...", seq);
00816 
00817             if (isFirstTime) {
00818                 if (! (getenv("ASC_LOG_ALL") && atoi(getenv("ASC_LOG_ALL")) > 0) )
00819                     needLog = false;
00820                 isFirstTime = false;
00821             }
00822         }
00823     }
00824 
00825 
00826     static int mainThreadId = 0;
00827 
00828     static void cleanup(const char* msg) {
00829         if (gettid() == mainThreadId) ABORT("%s", msg);
00830     }
00831 
00832     static void on_SIGPIPE(int signum) {
00833         cleanup("pipe peer ended first, no problem");
00834     }
00835     static void on_SIGINT(int signum) {
00836         cleanup("SIGINT(Ctl+C)");
00837     }
00838     static void on_SIGHUP(int signum) {
00839         cleanup("SIGHUP(adb shell terminated)");
00840     }
00841 
00842     extern "C" int main(int argc, char** argv) {
00843         status_t err;
00844 
00845         mainThreadId = gettid();
00846         LOG("set sig handler for SIGINT, SIGHUP, SIGPIPE");
00847         signal(SIGINT, on_SIGINT);
00848         signal(SIGHUP, on_SIGHUP);
00849         signal(SIGPIPE, on_SIGPIPE);
00850 
00851         ASC asc;
00852         memset(&asc, 0, sizeof(ASC));
00853         asc.w = argc>1 && atoi(argv[1])> 0 ? atoi(argv[1]) : 0;
00854         asc.h = argc>2 && atoi(argv[2])> 0 ? atoi(argv[2]) : 0;
00855 
00856         asc_init(asc);
00857 
00858         // const char* vformat = "video/x-vnd.on2.vp8";
00859         const char* vformat = "video/avc";
00860         // const char* vformat = "video/mp4v-es";
00861 
00862         sp<AMessage> format = new AMessage;
00863         format->setInt32("width", capture_w);
00864         format->setInt32("height", capture_h);
00865         format->setString("mime", vformat);
00866         format->setInt32("color-format", 0x7F000789/*OMX_COLOR_FormatAndroidOpaque*/);
00867         format->setInt32("bitrate", 4000000);
00868         format->setFloat("frame-rate", 30);
00869         format->setInt32("i-frame-interval", 1);
00870 
00871         LOG("Creating ALooper");
00872         sp<ALooper> looper = new ALooper;
00873         looper->setName("screenrecord_looper");
00874         LOG("Starting ALooper");
00875         looper->start();
00876 
00877         LOG("Creating codec");
00878         codec = MediaCodec::CreateByType(looper, vformat, true/*encoder*/);
00879         if (codec.get() == NULL) ABORT("ERROR: unable to create codec instance");
00880         LOG("configure codec");
00881         static void* nullPtr = NULL;
00882         #if (ANDROID_VER>=440)
00883             err = codec->configure(format, *(sp<Surface>*)&nullPtr, *(sp<ICrypto>*)&nullPtr, 1/*CONFIGURE_FLAG_ENCODE*/);
00884         #elif (ANDROID_VER>=420)
00885             err = codec->configure(format, *(sp<SurfaceTextureClient>*)&nullPtr, *(sp<ICrypto>*)&nullPtr, 1/*CONFIGURE_FLAG_ENCODE*/);
00886         #endif
00887         if (err) ABORT("ERROR: unable to configure codec (err=%d)", err);
00888 
00889         LOG("Starting codec");
00890         err = codec->start();
00891         if (err) ABORT("ERROR: unable to start codec (err=%d)", err);
00892 
00893         Vector<sp<ABuffer> > obfs;
00894         LOG("getOutputBuffers");
00895         err = codec->getOutputBuffers(&obfs);
00896         if (err) ABORT("getOutputBuffers ret:%d", err);
00897         LOG("obfs cnt %d", obfs.size());
00898 
00899         LOG("getInputBuffers");
00900         err = codec->getInputBuffers(&ibfs);
00901         if (err) ABORT("getInputBuffers ret:%d", err);
00902         LOG("ibfs cnt %d", ibfs.size());
00903 
00904         pthread_t thd_feed_input;
00905         err = pthread_create(&thd_feed_input, NULL, thread_feed_input, NULL); 
00906         if (err) ABORT("pthread_create err %d", err);
00907 
00908         while (true) {
00909             size_t bufIndex, offset, size;
00910             int64_t ptsUsec;
00911             uint32_t flags;
00912 
00913             LOG("dequeueOutputBuffer");
00914             err = codec->dequeueOutputBuffer(&bufIndex, &offset, &size, &ptsUsec, &flags, 250000);
00915             switch (err) {
00916             case 0:
00917                 if ((flags & MediaCodec::BUFFER_FLAG_CODECCONFIG) != 0) {
00918                     LOG("Got codec config buffer (%u bytes); ignoring", size);
00919                     size = 0;
00920                 }
00921                 if (size != 0) {
00922                     LOG("Got data in buffer %d, size=%d, pts=%lld", bufIndex, size, ptsUsec);
00923                 }
00924 
00925                 LOG("releaseOutputBuffer");
00926                 err = codec->releaseOutputBuffer(bufIndex);
00927                 LOG("releaseOutputBuffer ret:%d", err);
00928                 break;
00929             default:
00930                 LOG("dequeueOutputBuffer ret:%d", err);
00931                 // exit(0);
00932                 // return err;
00933             }
00934         }
00935 
00936         LOG("joinThreadPool");
00937         IPCThreadState::self()->joinThreadPool(/*isMain*/true);
00938         ABORT("unexpected here");
00939         return 0;
00940     }
00941 #endif


dji_ronin
Author(s):
autogenerated on Sat Jun 8 2019 20:15:31