code done

This commit is contained in:
AiYangSky 2023-12-21 17:33:06 +08:00
parent 9f35bf476e
commit 5d2e5b0250
11 changed files with 702 additions and 124 deletions

View File

@ -11,8 +11,8 @@ enum class CameraType : int
// 未知相机
NONE = 0X00001000,
// 标准opencv框架下的相机
WEBCAM = 0X00001001,
V4L2CAM = 0X00001002,
V4L2CAM = 0X00001001,
WEBCAM = 0X00001002,
// 视频文件
VIDEOFILE = 0X00002001,
// 普通流媒体相机

View File

@ -1,32 +1,29 @@
/*
* @Description:
* @Description: G1相机的具体功能实现
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-20 19:05:13
* @LastEditTime: 2023-12-21 11:42:40
* @FilePath: /SpireCV/video_io/driver/sv_camera_G1.cpp
*/
#include "../sv_camera_privately.h"
#include <fstream>
#include <map>
#include <iterator>
class sv_camera_G1 : public sv_p::CameraBase
{
private:
std::string _ip;
uint16_t _port = 554;
public:
bool setStream(const std::string &ip, uint16_t port);
sv::CameraType getType(void) { return sv::CameraType::G1; }
std::string getName(void) { return _ip; }
bool open(void);
public:
sv_camera_G1(int timeOut);
~sv_camera_G1();
static CameraBase* creat(int timeOut)
static CameraBase *creat(int timeOut)
{
return new sv_camera_G1(timeOut);
}
@ -34,7 +31,6 @@ public:
sv_camera_G1::sv_camera_G1(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_G1::setStream(const std::string &ip, uint16_t port)
@ -61,10 +57,10 @@ const static uint32_t imageWList[3] = {2704, 1920, 1280};
// 无论如何都用gst打开 因此安装的时候必须安装gst
bool sv_camera_G1::open(void)
{
bool ret = false;
std::ostringstream pipeline;
pipeline << "rtspsrc location = rtsp://" << this->_ip << ":"
<< this->_port << "/H264?W=";
pipeline << "rtspsrc location = rtsp://" << this->_ip << ":554/H264?W=";
// 判断尺寸是否合法 不合法则找最高画质进行缩放
uint8_t i;
@ -104,10 +100,14 @@ bool sv_camera_G1::open(void)
#endif
pipeline << " ! videoconvert ! video/x-raw,format=(string)BGR ! appsink sync=false";
this->cap.open(pipeline.str(), cv::CAP_GSTREAMER);
if (this->cap.open(pipeline.str(), cv::CAP_GSTREAMER))
{
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
ret = true;
}
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
return ret;
}

View File

@ -0,0 +1,85 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 17:27:22
* @FilePath: /SpireCV/video_io/driver/sv_camera_GX40.cpp
*/
#include "../sv_camera_privately.h"
#include <fstream>
class sv_camera_GX40 : public sv_p::CameraBase
{
private:
std::string _ip;
uint16_t _port = 554;
public:
bool setStream(const std::string &ip, uint16_t port);
sv::CameraType getType(void) { return sv::CameraType::GX40; }
std::string getName(void) { return _ip; }
bool open(void);
sv_camera_GX40(int timeOut);
~sv_camera_GX40();
static CameraBase *creat(int timeOut)
{
return new sv_camera_GX40(timeOut);
}
};
sv_camera_GX40::sv_camera_GX40(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_GX40::setStream(const std::string &ip, uint16_t port)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_ip = ip;
this->_port = port;
ret = true;
}
return ret;
}
// 无论如何都用gst打开 因此安装的时候必须安装gst
bool sv_camera_GX40::open(void)
{
bool ret = false;
std::ostringstream pipeline;
pipeline << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! application/x-rtp,media=video ! "
<< "rtph265depay ! parsebin ! ";
#ifdef PLATFORM_JETSON
pipeline << "nvv4l2decoder ! nvvidconv flip-method=4 ! ";
#else
pipeline << "avdec_h265 ! videoscale ! ";
#endif
pipeline << "video/x-raw,format=(string)BGRx"
<< ",width=(int)" << this->getW()
<< ",height=(int)" << this->getH()
<< " ";
#ifndef PLATFORM_JETSON
pipeline << "! videoflip video-direction=4 ";
#endif
pipeline << " ! videoconvert ! video/x-raw,format=(string)BGR ! appsink sync=false";
if (this->cap.open(pipeline.str(), cv::CAP_GSTREAMER))
{
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
ret = true;
}
return ret;
}

View File

@ -0,0 +1,78 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 17:10:30
* @FilePath: /SpireCV/video_io/driver/sv_camera_MC1.cpp
*/
#include "../sv_camera_privately.h"
#include <fstream>
class sv_camera_MC1 : public sv_p::CameraBase
{
private:
int _index = -2;
public:
bool setIndex(int index);
sv::CameraType getType(void) { return sv::CameraType::MC1; }
bool open(void);
sv_camera_MC1(int timeOut);
~sv_camera_MC1();
static CameraBase *creat(int timeOut)
{
#ifdef PLATFORM_JETSON
return new sv_camera_MC1(timeOut);
#else
throw std::runtime_error("SpireCV (101) Camera not supported except allspark");
return nullptr;
#endif
}
};
sv_camera_MC1::sv_camera_MC1(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_MC1::setIndex(int index)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_index = index;
ret = true;
}
return ret;
}
// 普通的mipi相机 采用 v4l2 框架打开
bool sv_camera_MC1::open(void)
{
bool ret = false;
std::ostringstream pipeline;
pipeline << "nvarguscamerasrc sensor-id=" << this->_index;
pipeline << " ! video/x-raw,video/x-raw(memory:NVMM),"
<< "width=(int)" << this->getW()
<< "height=(int)" << this->getH()
<< "framerate=" << this->getExpectFps() << "/1 !"
<< " nvvidconv flip-method=0 ! video/x-raw,format=(string)BGRx !"
<< " videoconvert ! video/x-raw, format=(string)BGR ! appsink";
if (this->cap.open(pipeline.str(), cv::CAP_GSTREAMER))
{
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
ret = true;
}
return ret;
}

View File

@ -0,0 +1,149 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-21 10:45:50
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 11:26:43
* @FilePath: /SpireCV/video_io/driver/sv_camera_V4L2s.cpp
*/
#include "../sv_camera_privately.h"
class sv_camera_V4L2 : public sv_p::CameraBase
{
private:
int _index = -1;
std::string _name = "\0";
public:
bool setName(const std::string &name);
bool setIndex(int index);
virtual sv::CameraType getType(void) { return sv::CameraType::V4L2CAM; }
std::string getName(void) { return this->_name; }
bool open(void);
sv_camera_V4L2(int timeOut);
~sv_camera_V4L2();
static CameraBase *creat(int timeOut)
{
return new sv_camera_V4L2(timeOut);
}
};
sv_camera_V4L2::sv_camera_V4L2(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_V4L2::setName(const std::string &name)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_name = name;
ret = true;
}
return ret;
}
bool sv_camera_V4L2::setIndex(int index)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_index = index;
ret = true;
}
return ret;
}
bool sv_camera_V4L2::open(void)
{
bool ret = false;
if (this->_index >= 0)
{
ret = this->cap.open(this->_index, cv::CAP_V4L2);
}
if (!ret)
{
if (this->_name != "\0")
{
ret = this->cap.open(this->_name, cv::CAP_V4L2);
}
}
if (ret)
{
// 设置属性
this->setFps(this->getExpectFps());
this->setBrightness(this->getBrightness());
this->setContrast(this->getContrast());
this->setSaturation(this->getSaturation());
this->setHue(this->getHue());
this->setExposure(this->getExposure());
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
}
return ret;
}
class sv_camera_WEBCAM : public sv_camera_V4L2
{
public:
sv::CameraType getType(void) { return sv::CameraType::WEBCAM; }
sv_camera_WEBCAM(int timeOut);
~sv_camera_WEBCAM();
static CameraBase *creat(int timeOut)
{
return new sv_camera_WEBCAM(timeOut);
}
};
sv_camera_WEBCAM::sv_camera_WEBCAM(int timeOut) : sv_camera_V4L2(timeOut)
{
}
class sv_camera_Q10 : public sv_camera_V4L2
{
public:
sv::CameraType getType(void) { return sv::CameraType::Q10; }
sv_camera_Q10(int timeOut);
~sv_camera_Q10();
static CameraBase *creat(int timeOut)
{
return new sv_camera_Q10(timeOut);
}
};
sv_camera_Q10::sv_camera_Q10(int timeOut) : sv_camera_V4L2(timeOut)
{
}
class sv_camera_NONE : public sv_camera_V4L2
{
public:
sv::CameraType getType(void) { return sv::CameraType::NONE; }
sv_camera_NONE(int timeOut);
~sv_camera_NONE();
static CameraBase *creat(int timeOut)
{
return new sv_camera_NONE(timeOut);
}
};
sv_camera_NONE::sv_camera_NONE(int timeOut) : sv_camera_V4L2(timeOut)
{
}

View File

@ -0,0 +1,79 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-21 11:30:40
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 11:43:08
* @FilePath: /SpireCV/video_io/driver/sv_camera_file.cpp
*/
#include "../sv_camera_privately.h"
class sv_camera_FILE : public sv_p::CameraBase
{
private:
std::string _name = "\0";
public:
bool setName(const std::string &name);
virtual sv::CameraType getType(void) { return sv::CameraType::VIDEOFILE; }
std::string getName(void) { return this->_name; }
bool open(void);
bool read(cv::Mat &image)
{
return this->cap.read(image);
}
bool readNoBlock(cv::Mat &image)
{
return this->read(image);
}
sv_camera_FILE(int timeOut);
~sv_camera_FILE();
static CameraBase *creat(int timeOut)
{
return new sv_camera_FILE(timeOut);
}
};
sv_camera_FILE::sv_camera_FILE(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_FILE::setName(const std::string &name)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_name = name;
ret = true;
}
return ret;
}
bool sv_camera_FILE::open(void)
{
bool ret = false;
if (this->_name != "\0")
{
ret = this->cap.open(this->_name);
}
if (ret)
{
// 设置属性
this->setFps(this->getExpectFps());
this->setBrightness(this->getBrightness());
this->setContrast(this->getContrast());
this->setSaturation(this->getSaturation());
this->setHue(this->getHue());
this->setExposure(this->getExposure());
}
return ret;
}

View File

@ -0,0 +1,95 @@
/*
* @Description: G1相机的具体功能实现
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 14:40:30
* @FilePath: /SpireCV/video_io/driver/sv_camera_mipi.cpp
*/
#include "../sv_camera_privately.h"
#include <fstream>
class sv_camera_MIPI : public sv_p::CameraBase
{
private:
int _index = -2;
std::string _name = "\0";
public:
bool setName(const std::string &name);
bool setIndex(int index);
sv::CameraType getType(void) { return sv::CameraType::MIPI; }
std::string getName(void) { return _name; }
bool open(void);
sv_camera_MIPI(int timeOut);
~sv_camera_MIPI();
static CameraBase *creat(int timeOut)
{
return new sv_camera_MIPI(timeOut);
}
};
sv_camera_MIPI::sv_camera_MIPI(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_MIPI::setName(const std::string &name)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_name = name;
ret = true;
}
return ret;
}
bool sv_camera_MIPI::setIndex(int index)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_index = index;
ret = true;
}
return ret;
}
// 普通的mipi相机 采用 v4l2 框架打开
bool sv_camera_MIPI::open(void)
{
bool ret = false;
std::ostringstream pipeline;
pipeline << "v4l2src ";
if (this->_name != "\0")
{
pipeline << "device=" << this->_name << " !";
}
else if (this->_index != -2)
{
pipeline << "device-fd=" << this->_index << " !";
}
pipeline << " video/x-raw,format=(string)NV12,"
<< "width=(int)" << this->getW()
<< "height=(int)" << this->getH()
<< "framerate=" << this->getExpectFps() << "/1 !"
<< " videoconvert ! video/x-raw, format=(string)BGR ! appsink";
if (this->cap.open(pipeline.str(), cv::CAP_GSTREAMER))
{
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
ret = true;
}
return ret;
}

View File

@ -0,0 +1,74 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-21 11:30:40
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 11:43:16
* @FilePath: /SpireCV/video_io/driver/sv_camera_streaming.cpp
*/
#include "../sv_camera_privately.h"
class sv_camera_Streaming : public sv_p::CameraBase
{
private:
std::string _name = "\0";
public:
bool setName(const std::string &name);
virtual sv::CameraType getType(void) { return sv::CameraType::STREAMING; }
std::string getName(void) { return this->_name; }
bool open(void);
sv_camera_Streaming(int timeOut);
~sv_camera_Streaming();
static CameraBase *creat(int timeOut)
{
return new sv_camera_Streaming(timeOut);
}
};
sv_camera_Streaming::sv_camera_Streaming(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_Streaming::setName(const std::string &name)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_name = name;
ret = true;
}
return ret;
}
bool sv_camera_Streaming::open(void)
{
bool ret = false;
if (this->_name != "\0")
{
ret = this->cap.open(this->_name);
}
if (ret)
{
// 设置属性
this->setFps(this->getExpectFps());
this->setBrightness(this->getBrightness());
this->setContrast(this->getContrast());
this->setSaturation(this->getSaturation());
this->setHue(this->getHue());
this->setExposure(this->getExposure());
// 开启读取线程
std::thread readLoop(&CameraBase::readThread, this);
this->readThreadHandle = readLoop.native_handle();
readLoop.detach();
}
return ret;
}

View File

@ -1,23 +1,36 @@
#include "sv_camera_privately.h"
#include "sv_camera.h"
#include "driver/sv_camera_G1.cpp"
#include "driver/sv_camera_V4L2s.cpp"
#include "driver/sv_camera_file.cpp"
#include "driver/sv_camera_streaming.cpp"
#include "driver/sv_camera_mipi.cpp"
#include "driver/sv_camera_MC1.cpp"
#include "driver/sv_camera_GX40.cpp"
#include <map>
#include <iterator>
sv_p::CameraBase *cameraCreatEmpty(int timeOut)
{
throw std::runtime_error("SpireCV (101) Camera not supported");
return nullptr;
}
typedef sv_p::CameraBase *(*cameraCreat)(int timeOut);
static std::map<sv::CameraType, cameraCreat> svCameraList =
{
{sv::CameraType::NONE, nullptr},
{sv::CameraType::WEBCAM, nullptr},
{sv::CameraType::V4L2CAM, nullptr},
{sv::CameraType::VIDEOFILE, nullptr},
{sv::CameraType::STREAMING, nullptr},
{sv::CameraType::MIPI, nullptr},
{sv::CameraType::G1, nullptr},
{sv::CameraType::Q10, nullptr},
{sv::CameraType::GX40, nullptr},
{sv::CameraType::MC1, nullptr},
{sv::CameraType::VIRTUAL, nullptr}};
{sv::CameraType::NONE, sv_camera_NONE::creat},
{sv::CameraType::WEBCAM, sv_camera_WEBCAM::creat},
{sv::CameraType::V4L2CAM, sv_camera_V4L2::creat},
{sv::CameraType::VIDEOFILE, sv_camera_FILE::creat},
{sv::CameraType::STREAMING, sv_camera_Streaming::creat},
{sv::CameraType::MIPI, sv_camera_MIPI::creat},
{sv::CameraType::G1, sv_camera_G1::creat},
{sv::CameraType::Q10, sv_camera_Q10::creat},
{sv::CameraType::GX40, sv_camera_GX40::creat},
{sv::CameraType::MC1, sv_camera_MC1::creat},
{sv::CameraType::VIRTUAL, cameraCreatEmpty}};
static sv_p::CameraBase *svCreatCamera(sv::CameraType type, int timeOut)
{
@ -31,7 +44,7 @@ static sv_p::CameraBase *svCreatCamera(sv::CameraType type, int timeOut)
sv::Camera::Camera(CameraType type, int timeOut)
{
this->dev = svCreatCamera(type,timeOut);
this->dev = svCreatCamera(type, timeOut);
}
sv::Camera::~Camera()

View File

@ -1,4 +1,5 @@
#include "sv_camera_privately.h"
#include "iostream"
sv_p::CameraBase::CameraBase(int timeOut)
{
@ -8,94 +9,33 @@ sv_p::CameraBase::CameraBase(int timeOut)
void sv_p::CameraBase::readThread(void)
{
int count = 0;
while (this->cap.isOpened())
{
std::this_thread::sleep_for(std::chrono::milliseconds(1));
if (this->cap.grab())
{
std::lock_guard<std::mutex> locker(this->frameMutex);
this->cap.retrieve(this->imageBuff);
this->frameEmpty.notify_all();
count = 0;
isGot = true;
// 统计输入的瞬时帧率
this->fpsCurr = 1000.0f / count;
count = 0;
}
else
{
count++;
if (count > this->_timeOut)
{
// 超时则主动关闭相机
this->cap.release();
// 抛出异常 并返回
// throw std::runtime_error("SpireCV (101) Camera has offline, check CAMERA!");
return;
}
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
}
#define PARAM_SET_CHECK(param, value) param = (value > 0 ? value : param)
void sv_p::CameraBase::setWH(int width, int height)
{
if (!this->cap.isOpened())
{
PARAM_SET_CHECK(this->_width, width);
PARAM_SET_CHECK(this->_height, height);
}
}
void sv_p::CameraBase::setFps(int fps)
{
PARAM_SET_CHECK(this->_fps, fps);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_FPS, fps);
}
}
void sv_p::CameraBase::setBrightness(double brightness)
{
PARAM_SET_CHECK(this->_brightness, brightness);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_BRIGHTNESS, brightness);
}
}
void sv_p::CameraBase::setContrast(double contrast)
{
PARAM_SET_CHECK(this->_contrast, contrast);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_CONTRAST, contrast);
}
}
void sv_p::CameraBase::setSaturation(double saturation)
{
PARAM_SET_CHECK(this->_saturation, saturation);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_SATURATION, saturation);
}
}
void sv_p::CameraBase::setHue(double hue)
{
PARAM_SET_CHECK(this->_hue, hue);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_HUE, hue);
}
}
void sv_p::CameraBase::setExposure(double exposure)
{
PARAM_SET_CHECK(this->_exposure, exposure);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_EXPOSURE, exposure);
}
// 相机断开连接 记录事件后 退出线程
std::cout << "SpireCV (101) Camera has offline, check CAMERA!" << std::endl;
}
bool sv_p::CameraBase::read(cv::Mat &image)
@ -118,12 +58,77 @@ bool sv_p::CameraBase::readNoBlock(cv::Mat &image)
std::lock_guard<std::mutex> locker(this->frameMutex);
if (this->isGot)
{
this->imageBuff.copyTo(image);
isGot = false;
// 该情况下read()不会阻塞
ret = this->read(image);
}
return ret;
}
#define PARAM_SET_CHECK(param, value) param = (value > 0 ? value : param)
void sv_p::CameraBase::setWH(int width, int height)
{
if (!this->cap.isOpened())
{
PARAM_SET_CHECK(this->_width, width);
PARAM_SET_CHECK(this->_height, height);
}
}
void sv_p::CameraBase::setFps(int fps)
{
PARAM_SET_CHECK(this->_fps, fps);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_FPS, fps);
}
}
void sv_p::CameraBase::setBrightness(float brightness)
{
PARAM_SET_CHECK(this->_brightness, brightness);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_BRIGHTNESS, brightness);
}
}
void sv_p::CameraBase::setContrast(float contrast)
{
PARAM_SET_CHECK(this->_contrast, contrast);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_CONTRAST, contrast);
}
}
void sv_p::CameraBase::setSaturation(float saturation)
{
PARAM_SET_CHECK(this->_saturation, saturation);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_SATURATION, saturation);
}
}
void sv_p::CameraBase::setHue(float hue)
{
PARAM_SET_CHECK(this->_hue, hue);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_HUE, hue);
}
}
void sv_p::CameraBase::setExposure(float exposure)
{
PARAM_SET_CHECK(this->_exposure, exposure);
if (this->cap.isOpened())
{
this->cap.set(cv::CAP_PROP_EXPOSURE, exposure);
}
}
void sv_p::CameraBase::release(void)
{
if (this->cap.isOpened())

View File

@ -13,24 +13,24 @@ namespace sv_p
class CameraBase
{
private:
public:
// 图像的属性
int _width = 1280;
int _height = 720;
int _fps = 30;
double _brightness = -1;
double _contrast = -1;
double _saturation = -1;
double _hue = -1;
double _exposure = -1;
float _brightness = -1;
float _contrast = -1;
float _saturation = -1;
float _hue = -1;
float _exposure = -1;
int _timeOut;
int _timeOut = 500;
// 内部状态
double fpsCurr = -1;
float fpsCurr = -1;
bool isGot = false;
public:
// 内部变量
cv::Mat imageBuff;
std::mutex frameMutex;
@ -48,11 +48,11 @@ public:
// 扩展属性设置 默认调用opencv的实现
virtual void setFps(int fps);
virtual void setBrightness(double brightness);
virtual void setContrast(double contrast);
virtual void setSaturation(double saturation);
virtual void setHue(double hue);
virtual void setExposure(double exposure);
virtual void setBrightness(float brightness);
virtual void setContrast(float contrast);
virtual void setSaturation(float saturation);
virtual void setHue(float hue);
virtual void setExposure(float exposure);
// 属性获取的接口
virtual sv::CameraType getType(void) { return sv::CameraType::NONE; }
@ -62,12 +62,12 @@ public:
int getW(void) { return _width; }
int getH(void) { return _height; }
int getExpectFps(void) { return _fps; }
double getFps(void) { return fpsCurr; }
double getBrightness(void) { return _brightness; }
double getContrast(void) { return _contrast; }
double getSaturation(void) { return _saturation; }
double getHue(void) { return _hue; }
double getExposure(void) { return _exposure; }
float getFps(void) { return fpsCurr; }
float getBrightness(void) { return _brightness; }
float getContrast(void) { return _contrast; }
float getSaturation(void) { return _saturation; }
float getHue(void) { return _hue; }
float getExposure(void) { return _exposure; }
// 功能接口函数
virtual bool open(void) = 0;
@ -75,7 +75,7 @@ public:
virtual bool readNoBlock(cv::Mat &image);
virtual void release(void);
CameraBase(int timeOut);
CameraBase(int timeOut = 500);
~CameraBase();
};