瀏覽代碼

add usb_cam_python.

yuchuli 2 年之前
父節點
當前提交
5afe59b1aa

+ 2 - 1
src/driver/driver_camera_ioctl/main.cpp

@@ -300,7 +300,7 @@ int main(int argc, char *argv[])
 
     gstrcamera = xp.GetParam("cameraname","/dev/video0");
 
-     xp.GetParam("cameraname",gvideo_device_name_, std::string("/dev/video2"));
+     xp.GetParam("cameraname",gvideo_device_name_, std::string("/dev/video0"));
  //   gvideo_device_name_ = xp.GetParam("video_device", std::string("/dev/video5"));
     gbrightness_ =  xp.GetParam("brightness",  -1); //0-255, -1 "leave alone"
     gcontrast_ = xp.GetParam("contrast",  -1); //0-255, -1 "leave alone"
@@ -316,6 +316,7 @@ int main(int argc, char *argv[])
     // enable/disable autofocus
     gautofocus_  = xp.GetParam("autofocus", false);
 
+
     gfocus_ = xp.GetParam("focus", -1); //0-255, -1 "leave alone"
     // enable/disable autoexposure
     gautoexposure_ = xp.GetParam("autoexposure",  true);

+ 36 - 0
src/driver/driver_camera_ioctl/pythonusbcam.py

@@ -0,0 +1,36 @@
+
+import ctypes
+import time
+import cv2 as cv
+import numpy as np
+
+mylib = ctypes.cdll.LoadLibrary("./libusb_cam_python.so")
+
+
+char_arr100 = ctypes.c_char*10000000
+y = char_arr100()
+
+def showpic():
+    str="hello"
+    i = 0;
+    nlenx = ctypes.c_int*2
+    nlen = nlenx()
+    mylib.StartCam("/dev/video0",1920,1080,30);
+    while i< 10000:
+    	nRtn = mylib.GetJPEGData("/dev/video0",y,nlen);
+        if(nRtn>0):
+		xdata = np.frombuffer(y,count = nlen[0])
+		matx = cv.imdecode(xdata, cv.IMREAD_COLOR );
+		cv.imshow("showing",matx)
+		cv.waitKey(1)
+		print nRtn
+	else :
+		time.sleep(0.001);
+		
+    str="exit"
+    print(str);
+
+
+if __name__ == "__main__":
+    print ('This is main ,for show pic from c++')
+    showpic()

+ 54 - 22
src/driver/driver_camera_ioctl/usb_cam.cpp

@@ -54,7 +54,7 @@
 
 #include <usb_cam.h>
 
-#include <QDateTime>
+//#include <QDateTime>
 #include <iostream>
 
 #define CLEAR(x) memset (&(x), 0, sizeof (x))
@@ -63,7 +63,8 @@ namespace usb_cam {
 
 static void errno_exit(const char * s)
 {
-  qDebug("%s error %d, %s", s, errno, strerror(errno));
+    std::cout<<s<<" error "<<errno<<" "<<strerror(errno)<<std::endl;
+//  qDebug("%s error %d, %s", s, errno, strerror(errno));
   exit(EXIT_FAILURE);
 }
 
@@ -373,7 +374,8 @@ int UsbCam::init_mjpeg_decoder(int image_width, int image_height)
   avcodec_ = avcodec_find_decoder(AV_CODEC_ID_MJPEG);
   if (!avcodec_)
   {
-    qDebug("Could not find MJPEG decoder");
+      std::cout<<" Could not find MJPEG decoder "<<std::endl;
+ //   qDebug("Could not find MJPEG decoder");
     return 0;
   }
 
@@ -403,7 +405,8 @@ int UsbCam::init_mjpeg_decoder(int image_width, int image_height)
   /* open it */
   if (avcodec_open2(avcodec_context_, avcodec_, &avoptions_) < 0)
   {
-    qDebug("Could not open MJPEG Decoder");
+      std::cout<<" Could not find MJPEG decoder "<<std::endl;
+//    qDebug("Could not open MJPEG Decoder");
     return 0;
   }
   return 1;
@@ -426,7 +429,8 @@ void UsbCam::mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels)
 
   if (decoded_len < 0)
   {
-    qDebug("Error while decoding frame.");
+      std::cout<<" Error while decoding frame."<<std::endl;
+//    qDebug("Error while decoding frame.");
     return;
   }
 #else
@@ -435,7 +439,8 @@ void UsbCam::mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels)
 
   if (!got_picture)
   {
-    qDebug("Webcam: expected picture but didn't get it...");
+      std::cout<<" Webcam: expected picture but didn't get it... "<<std::endl;
+//    qDebug("Webcam: expected picture but didn't get it...");
     return;
   }
 
@@ -444,7 +449,8 @@ void UsbCam::mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels)
   int pic_size = avpicture_get_size(avcodec_context_->pix_fmt, xsize, ysize);
   if (pic_size != avframe_camera_size_)
   {
-    qDebug("outbuf size mismatch.  pic_size: %d bufsize: %d", pic_size, avframe_camera_size_);
+      std::cout<<"outbuf size mismatch.  pic_size:"<<pic_size<<" bufsize: "<<avframe_camera_size_<<std::endl;
+//    qDebug("outbuf size mismatch.  pic_size: %d bufsize: %d", pic_size, avframe_camera_size_);
     return;
   }
 
@@ -457,7 +463,8 @@ void UsbCam::mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels)
   int size = avpicture_layout((AVPicture *)avframe_rgb_, AV_PIX_FMT_RGB24, xsize, ysize, (uint8_t *)RGB, avframe_rgb_size_);
   if (size != avframe_rgb_size_)
   {
-    qDebug("webcam: avpicture_layout error: %d", size);
+      std::cout<<" webcam: avpicture_layout error:  "<<size<<std::endl;
+//    qDebug("webcam: avpicture_layout error: %d", size);
     return;
   }
 }
@@ -720,7 +727,8 @@ void UsbCam::init_read(unsigned int buffer_size)
 
   if (!buffers_)
   {
-    qDebug("Out of memory");
+      std::cout<<"Out of memory"<<std::endl;
+//    qDebug("Out of memory");
     exit(EXIT_FAILURE);
   }
 
@@ -729,7 +737,8 @@ void UsbCam::init_read(unsigned int buffer_size)
 
   if (!buffers_[0].start)
   {
-    qDebug("Out of memory");
+      std::cout<<"Out of memory"<<std::endl;
+//    qDebug("Out of memory");
     exit(EXIT_FAILURE);
   }
 }
@@ -826,7 +835,8 @@ void UsbCam::init_userp(unsigned int buffer_size)
 
   if (!buffers_)
   {
-    qDebug("Out of memory");
+      std::cout<<"Out of memory"<<std::endl;
+//    qDebug("Out of memory");
     exit(EXIT_FAILURE);
   }
 
@@ -837,7 +847,8 @@ void UsbCam::init_userp(unsigned int buffer_size)
 
     if (!buffers_[n_buffers_].start)
     {
-      qDebug("Out of memory");
+        std::cout<<"Out of memory"<<std::endl;
+//      qDebug("Out of memory");
       exit(EXIT_FAILURE);
     }
   }
@@ -957,14 +968,22 @@ void UsbCam::init_device(int image_width, int image_height, int framerate)
   if (xioctl(fd_, VIDIOC_G_PARM, &stream_params) < 0)
     errno_exit("Couldn't query v4l fps!");
 
-  qDebug("Capability flag: 0x%x", stream_params.parm.capture.capability);
+  std::cout<<"Capability flag: "<<stream_params.parm.capture.capability<<std::endl;
+//  qDebug("Capability flag: 0x%x", stream_params.parm.capture.capability);
 
   stream_params.parm.capture.timeperframe.numerator = 1;
   stream_params.parm.capture.timeperframe.denominator = framerate;
   if (xioctl(fd_, VIDIOC_S_PARM, &stream_params) < 0)
-    qDebug("Couldn't set camera framerate");
+  {
+      std::cout<<"Couldn't set camera framerate"<<std::endl;
+  }
+ //   qDebug("Couldn't set camera framerate");
   else
-    qDebug("Set framerate to be %i", framerate);
+  {
+      std::cout<<"Set framerate to be "<<framerate<<std::endl;
+//      qDebug("Set framerate to be %i", framerate);
+  }
+
 
   switch (io_)
   {
@@ -1049,10 +1068,12 @@ void UsbCam::start(const std::string& dev, io_method io_method,
   }
   else
   {
-    qDebug("Unknown pixel format.");
+    std::cout<<"Unknown pixel format."<<std::endl;
+//    qDebug("Unknown pixel format.");
     exit(EXIT_FAILURE);
   }
 
+
   open_device();
   init_device(image_width, image_height, framerate);
   start_capturing();
@@ -1116,7 +1137,8 @@ void UsbCam::grab_image(char *strdata, int *pnlen,const int nSize)
     grab_image();
     if(image_->image_size > nSize)
     {
-        qDebug("image size is %d . data buffer is %d small.",image_->image_size,nSize);
+        std::cout<<"image size is "<<image_->image_size<<" . data buffer is "<<nSize<<" small."<<std::endl;
+ //       qDebug("image size is %d . data buffer is %d small.",image_->image_size,nSize);
         *pnlen = 0;
         return;
     }
@@ -1149,7 +1171,8 @@ void UsbCam::grab_image()
 
   if (0 == r)
   {
-    qDebug("select timeout");
+      std::cout<<"select timeout."<<std::endl;
+ //   qDebug("select timeout");
     exit(EXIT_FAILURE);
   }
 
@@ -1175,13 +1198,15 @@ void UsbCam::set_auto_focus(int value)
     }
     else
     {
-      qDebug("V4L2_CID_FOCUS_AUTO is not supported");
+        std::cout<<" V4L2_CID_FOCUS_AUTO is not supported"<<std::endl;
+  //    qDebug("V4L2_CID_FOCUS_AUTO is not supported");
       return;
     }
   }
   else if (queryctrl.flags & V4L2_CTRL_FLAG_DISABLED)
   {
-    qDebug("V4L2_CID_FOCUS_AUTO is not supported");
+      std::cout<<" V4L2_CID_FOCUS_AUTO is not supported"<<std::endl;
+//    qDebug("V4L2_CID_FOCUS_AUTO is not supported");
     return;
   }
   else
@@ -1234,10 +1259,17 @@ void UsbCam::set_v4l_parameter(const std::string& param, const std::string& valu
     pclose(stream);
     // any output should be an error
     if (output.length() > 0)
-      qDebug("%s", output.c_str());
+    {
+        std::cout<<output<<std::endl;
+//      qDebug("%s", output.c_str());
+    }
   }
   else
-    qDebug("usb_cam_node could not run '%s'", cmd.c_str());
+  {
+      std::cout<<"usb_cam_node could not run '"<<cmd<<"'"<<std::endl;
+ //     qDebug("usb_cam_node could not run '%s'", cmd.c_str());
+  }
+
 }
 
 UsbCam::io_method UsbCam::io_method_from_string(const std::string& str)

+ 307 - 0
src/driver/driver_camera_ioctl/usb_cam_python.cpp

@@ -0,0 +1,307 @@
+#include "usb_cam_python.h"
+
+#include <vector>
+#include <iostream>
+
+#include <thread>
+#include <mutex>
+#include <condition_variable>
+
+
+namespace iv {
+
+struct threadcam
+{
+    std::thread * mpthread;
+    std::string mstrvideoname;
+    std::shared_ptr<char> mpstr_data;
+    int mndatasize;
+    std::mutex mmutexdata;
+    usb_cam::UsbCam * mpusbcam;
+    bool mbRun;
+    bool mbUpdate;
+    std::condition_variable mcv;
+    std::mutex mmutexcv;
+};
+
+
+}
+
+std::vector<iv::threadcam * >  gvectorthreadcam;
+
+std::mutex gmutex;
+
+
+
+using namespace  usb_cam;
+
+bool gstreaming_status_;
+int gimage_width_, gimage_height_, gframerate_, gexposure_, gbrightness_, gcontrast_, gsaturation_, gsharpness_, gfocus_,
+    gwhite_balance_, ggain_;
+bool gautofocus_, gautoexposure_, gauto_white_balance_;
+
+
+
+void setdefaultcvalue()
+{
+    gbrightness_ = -1;// xp.GetParam("brightness",  -1); //0-255, -1 "leave alone"
+    gcontrast_ = -1;//xp.GetParam("contrast",  -1); //0-255, -1 "leave alone"
+    gsaturation_ =  -1;//xp.GetParam("saturation",  -1); //0-255, -1 "leave alone"
+    gsharpness_ = -1;//xp.GetParam("sharpness",  -1); //0-255, -1 "leave alone"
+    // possible values: mmap, read, userptr
+//    gio_method_name_ = xp.GetParam("io_method",  std::string("mmap"));
+//    gimage_width_ = xp.GetParam("image_width", 1920);
+//    gimage_height_ = xp.GetParam("image_height",  1080);
+//    gframerate_ =  xp.GetParam("framerate",  30);
+    // possible values: yuyv, uyvy, mjpeg, yuvmono10, rgb24
+//    gpixel_format_name_ = xp.GetParam("pixel_format",  std::string("mjpeg"));
+    // enable/disable autofocus
+    gautofocus_  = false;//xp.GetParam("autofocus", false);
+
+
+    gfocus_ = -1;//xp.GetParam("focus", -1); //0-255, -1 "leave alone"
+    // enable/disable autoexposure
+    gautoexposure_ = true;//xp.GetParam("autoexposure",  true);
+    gexposure_ = 100;//xp.GetParam("exposure",  100);
+    ggain_ = -1;//xp.GetParam("gain",  -1); //0-100?, -1 "leave alone"
+    // enable/disable auto white balance temperature
+    gauto_white_balance_ = true;//xp.GetParam("auto_white_balance", true);
+    gwhite_balance_ = 4000;//xp.GetParam("white_balance", 4000);
+
+    // load the camera info
+//     xp.GetParam("camera_frame_id", img_.header.frame_id, std::string("head_camera"));
+//    gcamera_name_ = "head_camera";// xp.GetParam("camera_name",  std::string("head_camera"));
+//    gcamera_info_url_ = "";//xp.GetParam("camera_info_url",  std::string(""));
+}
+
+
+void threadcam(iv::threadcam * pthreadcam)
+{
+
+    while(pthreadcam->mbRun)
+    {
+        std::shared_ptr<char> mpstr_buf = std::shared_ptr<char>(new char[1000000]);
+        int nLen = 0;
+  //      std::cout<< "grab."<<std::endl;
+        pthreadcam->mpusbcam->grab_image(mpstr_buf.get(),&nLen,1000000);
+        if(nLen> 0)
+        {
+            pthreadcam->mmutexdata.lock();
+            pthreadcam->mndatasize = nLen;
+            pthreadcam->mpstr_data = mpstr_buf;
+            pthreadcam->mbUpdate = true;
+            pthreadcam->mmutexdata.unlock();
+            pthreadcam->mcv.notify_all();
+  //          std::cout<<std::chrono::system_clock::now().time_since_epoch().count()/1000<< " "<<nLen<<std::endl;
+        }
+        else
+        {
+            std::cout<<std::chrono::system_clock::now().time_since_epoch().count()/1000000<<" read camera "<<pthreadcam->mstrvideoname<<" fail."<<std::endl;
+            std::this_thread::sleep_for(std::chrono::milliseconds(100));
+        }
+    }
+
+    pthreadcam->mpusbcam->stop_capturing();
+    pthreadcam->mpusbcam->shutdown();
+    delete pthreadcam->mpusbcam;
+
+
+}
+
+
+extern "C"
+{
+
+int StartCam(const char * strvideoname,int image_width,int image_height,int image_framerate)
+{
+
+    usb_cam::UsbCam * pcamx = new usb_cam::UsbCam;
+
+    // set the IO method
+    UsbCam::io_method io_method = UsbCam::io_method_from_string("mmap");
+    if(io_method == UsbCam::IO_METHOD_UNKNOWN)
+    {
+        std::cout<<"Unknown IO method mmap "<<std::endl;
+      return 0;
+    }
+
+
+
+    // set the pixel format
+    UsbCam::pixel_format pixel_format = UsbCam::pixel_format_from_string("mjpeg");
+    if (pixel_format == UsbCam::PIXEL_FORMAT_UNKNOWN)
+    {
+        std::cout<<" Unknown pixel format mjpeg"<<std::endl;
+      return 0;
+    }
+
+//    std::cout<<"hear."<<std::endl;
+
+    std::cout<<"video name "<<strvideoname<<std::endl;
+
+
+
+    // start the camera
+    pcamx->start(strvideoname, io_method, pixel_format, image_width,
+             image_height, image_framerate);
+
+
+    setdefaultcvalue();
+
+
+
+
+    // set camera parameters
+    if (gbrightness_ >= 0)
+    {
+      pcamx->set_v4l_parameter("brightness", gbrightness_);
+    }
+
+    if (gcontrast_ >= 0)
+    {
+      pcamx->set_v4l_parameter("contrast", gcontrast_);
+    }
+
+    if (gsaturation_ >= 0)
+    {
+      pcamx->set_v4l_parameter("saturation", gsaturation_);
+    }
+
+    if (gsharpness_ >= 0)
+    {
+      pcamx->set_v4l_parameter("sharpness", gsharpness_);
+    }
+
+    if (ggain_ >= 0)
+    {
+      pcamx->set_v4l_parameter("gain", ggain_);
+    }
+
+    // check auto white balance
+    if (gauto_white_balance_)
+    {
+      pcamx->set_v4l_parameter("white_balance_temperature_auto", 1);
+    }
+    else
+    {
+      pcamx->set_v4l_parameter("white_balance_temperature_auto", 0);
+      pcamx->set_v4l_parameter("white_balance_temperature", gwhite_balance_);
+    }
+
+    // check auto exposure
+    if (!gautoexposure_)
+    {
+      // turn down exposure control (from max of 3)
+      pcamx->set_v4l_parameter("exposure_auto", 1);
+      // change the exposure level
+      pcamx->set_v4l_parameter("exposure_absolute", gexposure_);
+    }
+
+    // check auto focus
+    if (gautofocus_)
+    {
+      pcamx->set_auto_focus(1);
+      pcamx->set_v4l_parameter("focus_auto", 1);
+    }
+    else
+    {
+      pcamx->set_v4l_parameter("focus_auto", 0);
+      if (gfocus_ >= 0)
+      {
+        pcamx->set_v4l_parameter("focus_absolute", gfocus_);
+      }
+    }
+
+
+
+    pcamx->set_useRawMJPEG(true);
+
+    iv::threadcam  * xthreadcam = new iv::threadcam;
+    xthreadcam->mbRun = true;
+    xthreadcam->mbUpdate = false;
+    xthreadcam->mpusbcam = pcamx;
+    xthreadcam->mstrvideoname = strvideoname;
+
+
+    xthreadcam->mpthread = new std::thread(threadcam,xthreadcam);
+
+    gvectorthreadcam.push_back(xthreadcam);
+    return 1;
+}
+
+
+int GetJPEGData(char * strvideoname, char * str,int * x)
+{
+    std::string strvideo = strvideoname;
+
+    int nsize;
+    int i;
+    iv::threadcam * pthreadcam = NULL;
+    for(i=0;i<nsize;i++)
+    {
+        if(gvectorthreadcam[i]->mstrvideoname == strvideo)
+        {
+            pthreadcam = gvectorthreadcam[i];
+            break;
+        }
+    }
+
+    if(pthreadcam == NULL)
+    {
+        std::cout<<" video device not open."<<std::endl;
+        return 0;
+    }
+
+    int nRtn = 0;
+    pthreadcam->mmutexdata.lock();
+    if(pthreadcam->mbUpdate)
+    {
+//        str.copy(gstrbuf,gnLen);
+        memcpy(str,pthreadcam->mpstr_data.get(),pthreadcam->mndatasize);
+        nRtn = pthreadcam->mndatasize;
+        *x = pthreadcam->mndatasize;
+        pthreadcam->mbUpdate= false;
+    }
+    pthreadcam->mmutexdata.unlock();
+    return nRtn;
+}
+
+int StopCam(char * strvideoname)
+{
+    std::string strvideo = strvideoname;
+
+    int nsize;
+    int i;
+    iv::threadcam * pthreadcam = NULL;
+    int index;
+    gmutex.lock();
+    for(i=0;i<nsize;i++)
+    {
+        if(gvectorthreadcam[i]->mstrvideoname == strvideo)
+        {
+            pthreadcam = gvectorthreadcam[i];
+            index = i;
+            break;
+        }
+    }
+
+    if(pthreadcam == NULL)
+    {
+        std::cout<<" video device not open."<<std::endl;
+        gmutex.unlock();
+
+        return 0;
+    }
+
+    pthreadcam->mbRun = false;
+    pthreadcam->mpthread->join();
+    gvectorthreadcam.erase(gvectorthreadcam.begin() + index);
+
+    gmutex.unlock();
+
+
+}
+
+
+
+}

+ 6 - 0
src/driver/driver_camera_ioctl/usb_cam_python.h

@@ -0,0 +1,6 @@
+#ifndef USB_CAM_PYTHON_H
+#define USB_CAM_PYTHON_H
+
+#include "usb_cam.h"
+
+#endif // TESTPYTHONCPP_H

+ 41 - 0
src/driver/driver_camera_ioctl/usb_cam_python.pro

@@ -0,0 +1,41 @@
+QT -= gui
+
+QT -=core
+
+
+CONFIG += c++11
+
+TEMPLATE = lib
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += usb_cam.cpp \
+    usb_cam_python.cpp
+
+HEADERS += usb_cam.h \
+    usb_cam_python.h
+
+CONFIG += plugin
+
+
+# Default rules for deployment.
+unix {
+    target.path = /usr/lib
+}
+!isEmpty(target.path): INSTALLS += target
+
+LIBS +=-lpostproc -lswresample -lswscale -lavfilter -lavdevice -lavformat -lavcodec -lavutil -lm -ldl
+
+
+
+
+