Compare commits

...

5 Commits

Author SHA1 Message Date
AiYangSky fe18e3e0b6 build done 2023-12-21 18:46:16 +08:00
AiYangSky 5d2e5b0250 code done 2023-12-21 17:33:06 +08:00
AiYangSky 9f35bf476e add G1 camera 2023-12-20 19:05:47 +08:00
AiYangSky 173acc7036 add G1 camera 2023-12-20 18:55:51 +08:00
AiYangSky a0d3e258d9 camerabase done 2023-12-19 18:44:25 +08:00
34 changed files with 1549 additions and 315 deletions

View File

@ -119,7 +119,8 @@ set(
include/sv_mot.h
include/sv_color_line.h
include/sv_veri_det.h
include/sv_video_input.h
# include/sv_video_input.h
include/sv_camera.h
include/sv_video_output.h
include/sv_world.h
)

79
include/sv_camera.h Normal file
View File

@ -0,0 +1,79 @@
#ifndef __SV_CAMERA__
#define __SV_CAMERA__
#include "opencv2/opencv.hpp"
namespace sv
{
enum class CameraType : int
{
// 未知相机
NONE = 0X00001000,
// 标准opencv框架下的相机
V4L2CAM = 0X00001001,
WEBCAM = 0X00001002,
// 视频文件
VIDEOFILE = 0X00002001,
// 普通流媒体相机
STREAMING = 0X00004001,
// 普通的MIPI-CSI相机
MIPI = 0X00008001,
// 进行了传输优化适配的相机
G1 = 0X00010001,
Q10 = 0X00010002,
GX40 = 0X00010003,
MC1 = 0X00010004,
// 虚拟的相机设备 主要仿真接入
VIRTUAL = 0X00020001,
};
class Camera
{
private:
void *dev;
public:
// 构建时根据相机类型实例化对应的相机类
// timeOut: 相机连接超时时间;超过该时间没有读取到新的帧,则认为相机失去连接 单位ms
Camera(CameraType type, int timeOut = 500);
// 基本配置 必须调用下述的一个接口后才能open
bool setStream(const std::string &ip, int port);
bool setName(const std::string &name);
bool setIndex(int index);
// 基础功能
bool open(void);
bool read(cv::Mat &image);
bool readNoBlock(cv::Mat &image);
void release(void);
// 属性配置
void setWH(int width, int height);
void setFps(int fps);
void setBrightness(double brightness);
void setContrast(double contrast);
void setSaturation(double saturation);
void setHue(double hue);
void setExposure(double exposure);
// 获取属性
bool isActive(void);
CameraType getType(void);
std::string getName(void);
int getW(void);
int getH(void);
int getExpectFps(void);
double getFps(void);
double getBrightness(void);
double getContrast(void);
double getSaturation(void);
double getHue(void);
double getExposure(void);
~Camera();
};
}
#endif

View File

@ -326,59 +326,59 @@ protected:
};
enum class CameraType {NONE, WEBCAM, V4L2CAM, G1, Q10, MIPI, GX40};
// enum class CameraType {NONE, WEBCAM, V4L2CAM, G1, Q10, MIPI, GX40};
class CameraBase {
public:
CameraBase(CameraType type=CameraType::NONE, int id=0);
~CameraBase();
void open(CameraType type=CameraType::WEBCAM, int id=0);
bool read(cv::Mat& image);
void release();
// class CameraBase {
// public:
// CameraBase(CameraType type=CameraType::NONE, int id=0);
// ~CameraBase();
// void open(CameraType type=CameraType::WEBCAM, int id=0);
// bool read(cv::Mat& image);
// void release();
int getW();
int getH();
int getFps();
std::string getIp();
int getPort();
double getBrightness();
double getContrast();
double getSaturation();
double getHue();
double getExposure();
bool isRunning();
void setWH(int width, int height);
void setFps(int fps);
void setIp(std::string ip);
void setPort(int port);
void setBrightness(double brightness);
void setContrast(double contrast);
void setSaturation(double saturation);
void setHue(double hue);
void setExposure(double exposure);
protected:
virtual void openImpl();
void _run();
// int getW();
// int getH();
// int getFps();
// std::string getIp();
// int getPort();
// double getBrightness();
// double getContrast();
// double getSaturation();
// double getHue();
// double getExposure();
// bool isRunning();
// void setWH(int width, int height);
// void setFps(int fps);
// void setIp(std::string ip);
// void setPort(int port);
// void setBrightness(double brightness);
// void setContrast(double contrast);
// void setSaturation(double saturation);
// void setHue(double hue);
// void setExposure(double exposure);
// protected:
// virtual void openImpl();
// void _run();
bool _is_running;
bool _is_updated;
std::thread _tt;
cv::VideoCapture _cap;
cv::Mat _frame;
CameraType _type;
int _camera_id;
// bool _is_running;
// bool _is_updated;
// std::thread _tt;
// cv::VideoCapture _cap;
// cv::Mat _frame;
// CameraType _type;
// int _camera_id;
int _width;
int _height;
int _fps;
std::string _ip;
int _port;
double _brightness;
double _contrast;
double _saturation;
double _hue;
double _exposure;
};
// int _width;
// int _height;
// int _fps;
// std::string _ip;
// int _port;
// double _brightness;
// double _contrast;
// double _saturation;
// double _hue;
// double _exposure;
// };
void drawTargetsInFrame(

View File

@ -1,3 +1,4 @@
#if 0
#ifndef __SV_VIDEO_INPUT__
#define __SV_VIDEO_INPUT__
@ -25,3 +26,4 @@ protected:
}
#endif
#endif

View File

@ -39,6 +39,8 @@ the use of this software, even if advised of the possibility of such damage.
#include <sv_world.h>
#include "aruco_samples_utility.hpp"
#include "sv_camera.h"
using namespace std;
using namespace cv;
@ -146,10 +148,14 @@ int main(int argc, char *argv[]) {
}
// VideoCapture inputVideo;
sv::Camera inputVideo;
sv::Camera inputVideo(c_type);
inputVideo.setIndex(camId);
inputVideo.setStream("192.168.144.64",554);
inputVideo.setWH(imW, imH);
inputVideo.setFps(fps);
inputVideo.open(c_type, camId);
inputVideo.open();
int waitTime = 10;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -12,10 +13,12 @@ int main(int argc, char *argv[]) {
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(ad.image_width, ad.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,15 +2,17 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
int main(int argc, char *argv[]) {
// 打开摄像头
sv::Camera cap;
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
while (1)

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
using namespace sv;
@ -14,10 +15,11 @@ int main(int argc, char *argv[])
cld.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
cap.setWH(640, 480);
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cld.image_width, cld.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -12,10 +13,11 @@ int main(int argc, char *argv[]) {
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cod.image_width, cod.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -48,10 +49,11 @@ int main(int argc, char *argv[]) {
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cod.image_width, cod.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -12,10 +13,12 @@ int main(int argc, char *argv[]) {
ed.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(ed.image_width, ed.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -3,6 +3,7 @@
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include <map>
#include "sv_camera.h"
// 定义窗口名称
static const std::string RGB_WINDOW = "Image window";
@ -34,27 +35,6 @@ void gimbalNoTrack(void)
int main(int argc, char *argv[])
{
// 实例化吊舱
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
// 使用 /dev/ttyUSB0 作为控制串口
gimbal->setSerialPort("/dev/ttyUSB0");
// 以GimableCallback作为状态回调函数启用吊舱控制
gimbal->open(GimableCallback);
// 定义相机
sv::Camera cap;
// 设置相机流媒体地址为 192.168.2.64
cap.setIp("192.168.2.64");
// 设置获取画面分辨率为720P
cap.setWH(1280, 720);
// 设置视频帧率为30帧
cap.setFps(30);
// 开启相机
cap.open(sv::CameraType::G1);
// 定义一个新的窗口,可在上面进行框选操作
cv::namedWindow(RGB_WINDOW);
// 设置窗口操作回调函数,该函数实现整个框选逻辑
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
// 实例化 框选目标跟踪类
sv::SingleObjectTracker sot;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
@ -63,6 +43,37 @@ int main(int argc, char *argv[])
sv::CommonObjectDetector cod;
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// 实例化吊舱
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
// 使用 /dev/ttyUSB0 作为控制串口
gimbal->setSerialPort("/dev/ttyUSB0");
// 以GimableCallback作为状态回调函数启用吊舱控制
gimbal->open(GimableCallback);
// 打开摄像头
sv::Camera cap(sv::CameraType::G1);
cap.setStream("192.168.2.64",554);
cap.setWH(cod.image_width, cod.image_height);
cap.setFps(30);
cap.open(); // CameraID 0
// // 定义相机
// sv::Camera cap;
// // 设置相机流媒体地址为 192.168.2.64
// cap.setIp("192.168.2.64");
// // 设置获取画面分辨率为720P
// cap.setWH(1280, 720);
// // 设置视频帧率为30帧
// cap.setFps(30);
// // 开启相机
// cap.open(sv::CameraType::G1);
// 定义一个新的窗口,可在上面进行框选操作
cv::namedWindow(RGB_WINDOW);
// 设置窗口操作回调函数,该函数实现整个框选逻辑
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -3,6 +3,7 @@
// 包含SpireCV SDK头文件
#include <sv_world.h>
// #include "gimbal_tools.hpp"
#include "sv_camera.h"
using namespace std;
@ -34,31 +35,39 @@ void gimbalNoTrack(void)
int main(int argc, char *argv[])
{
// 实例化 圆形降落标志 检测器类
sv::LandingMarkerDetector lmd;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// 实例化吊舱
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
// 使用 /dev/ttyUSB0 作为控制串口
gimbal->setSerialPort("/dev/ttyUSB0");
// 以GimableCallback作为状态回调函数启用吊舱控制
gimbal->open(GimableCallback);
// 定义相机
sv::Camera cap;
// 设置相机流媒体地址为 192.168.2.64
cap.setIp("192.168.2.64");
// 设置获取画面分辨率为720P
cap.setWH(1280, 720);
// 设置视频帧率为30帧
// 打开摄像头
sv::Camera cap(sv::CameraType::G1);
cap.setStream("192.168.2.64", 554);
cap.setWH(lmd.image_width, lmd.image_height);
cap.setFps(30);
// 开启相机
cap.open(sv::CameraType::G1);
cap.open(); // CameraID 0
// // 定义相机
// sv::Camera cap;
// // 设置相机流媒体地址为 192.168.2.64
// cap.setIp("192.168.2.64");
// // 设置获取画面分辨率为720P
// cap.setWH(1280, 720);
// // 设置视频帧率为30帧
// cap.setFps(30);
// // 开启相机
// cap.open(sv::CameraType::G1);
// 定义一个窗口 才可以在上面操作
cv::namedWindow(RGB_WINDOW);
// 设置窗口操作回调函数,该函数实现吊舱控制
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
// 实例化 圆形降落标志 检测器类
sv::LandingMarkerDetector lmd;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -43,31 +44,40 @@ void onMouse(int event, int x, int y, int, void *);
int main(int argc, char *argv[])
{
// 实例化Aruco检测器类
sv::ArucoDetector ad;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// 实例化吊舱
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
// 使用 /dev/ttyUSB0 作为控制串口
gimbal->setSerialPort("/dev/ttyUSB0");
// 以gimableCallback作为状态回调函数启用吊舱控制
gimbal->open(gimableCallback);
// 定义相机
sv::Camera cap;
// 设置相机流媒体地址为 192.168.2.64
cap.setIp("192.168.2.64");
// 设置获取画面分辨率为720P
cap.setWH(1280, 720);
// 设置视频帧率为30帧
// 打开摄像头
sv::Camera cap(sv::CameraType::G1);
cap.setStream("192.168.2.64",554);
cap.setWH(ad.image_width, ad.image_height);
cap.setFps(30);
// 开启相机
cap.open(sv::CameraType::G1);
cap.open(); // CameraID 0
// // 定义相机
// sv::Camera cap;
// // 设置相机流媒体地址为 192.168.2.64
// cap.setIp("192.168.2.64");
// // 设置获取画面分辨率为720P
// cap.setWH(1280, 720);
// // 设置视频帧率为30帧
// cap.setFps(30);
// // 开启相机
// cap.open(sv::CameraType::G1);
// 定义一个窗口 才可以在上面操作
cv::namedWindow(RGB_WINDOW);
// 设置窗口操作回调函数,该函数实现吊舱控制
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
// 实例化Aruco检测器类
sv::ArucoDetector ad;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
sv::UDPServer udp;
// 实例化OpenCV的Mat类用于内存单帧图像

View File

@ -2,7 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
int main(int argc, char *argv[]) {
@ -11,11 +11,13 @@ int main(int argc, char *argv[]) {
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(lmd.image_width, lmd.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,6 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
@ -15,11 +16,13 @@ int main(int argc, char *argv[]) {
mot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
mot.init(&cod);
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cod.image_width, cod.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,7 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
// 定义窗口名称
@ -32,11 +32,13 @@ int main(int argc, char *argv[]) {
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1920x1080.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(sot.image_width, sot.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4");
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;

View File

@ -2,7 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
int main(int argc, char *argv[]) {
@ -11,11 +11,12 @@ int main(int argc, char *argv[]) {
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
cap.setWH(640, 480);
cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(ad.image_width, ad.image_height);
// cap.setFps(30);
cap.open(); // CameraID 0
sv::UDPServer udp;
// 实例化OpenCV的Mat类用于内存单帧图像

View File

@ -2,7 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
struct node
@ -25,11 +25,12 @@ int main(int argc, char *argv[])
sv::CommonObjectDetector cod;
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cod.image_width, cod.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,7 +2,7 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
int main(int argc, char *argv[]) {
@ -12,10 +12,12 @@ int main(int argc, char *argv[]) {
cod.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(cod.image_width, cod.image_height);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@ -2,15 +2,17 @@
#include <string>
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include "sv_camera.h"
using namespace std;
int main(int argc, char *argv[]) {
// 打开摄像头
sv::Camera cap;
// cap.setWH(1280, 720);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
// 打开摄像头
sv::Camera cap(sv::CameraType::WEBCAM);
cap.setIndex(0);
cap.setWH(1280, 720);
cap.setFps(30);
cap.open(); // CameraID 0
// 实例化视频推流类sv::VideoStreamer
sv::VideoStreamer streamer;

View File

@ -3,6 +3,7 @@
// 包含SpireCV SDK头文件
#include <sv_world.h>
#include <chrono>
#include "sv_camera.h"
// yaw roll pitch
double gimbalEulerAngle[3];
@ -143,14 +144,20 @@ int main(int argc, char *argv[])
std::cout << " pass... " << std::endl;
std::cout << " start image test " << std::endl;
sv::Camera cap;
cap.setIp(argv[2]);
// 打开摄像头
sv::Camera cap(sv::CameraType::G1);
cap.setStream(argv[2], 554);
cap.setWH(1280, 720);
cap.setFps(30);
cap.open(); // CameraID 0
cap.open(sv::CameraType::G1);
// sv::Camera cap;
// cap.setIp(argv[2]);
// cap.setWH(1280, 720);
// cap.setFps(30);
// cap.open(sv::CameraType::G1);
if (!cap.isRunning())
if (!cap.isActive())
{
std::cout << " gimbal image error , failed !!!!!" << std::endl;
return -1;

View File

@ -0,0 +1,106 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 17:56:47
* @FilePath: /SpireCV/video_io/driver/sv_camera_G1.cpp
*/
#include "sv_camera_privately.h"
#include <fstream>
class sv_camera_G1 : public sv_p::CameraBase
{
private:
std::string _ip;
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);
sv_camera_G1(int timeOut);
~sv_camera_G1();
static CameraBase *creat(int timeOut)
{
return new sv_camera_G1(timeOut);
}
};
sv_camera_G1::sv_camera_G1(int timeOut) : sv_p::CameraBase(timeOut)
{
}
bool sv_camera_G1::setStream(const std::string &ip, uint16_t port)
{
bool ret = false;
if (!this->cap.isOpened())
{
this->_ip = ip;
ret = true;
}
return ret;
}
const static uint32_t imageHList[3] = {1520, 1080, 720};
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 << ":554/H264?W=";
// 判断尺寸是否合法 不合法则找最高画质进行缩放
uint8_t i;
for (i = 0; i < 3; i++)
{
if (imageHList[i] <= this->getH())
{
if (imageWList[i] <= this->getW())
{
break;
}
}
}
// 在范围内
if (i < 3)
{
pipeline << imageWList[i] << "&H=" << imageHList[i];
}
else
{
pipeline << imageWList[2] << "&H=" << imageHList[2];
}
pipeline << "&FPS=" << this->getExpectFps() << "&BR=4000000 latency=100 "
<< "! application/x-rtp,media=video ! rtph264depay ! parsebin ! ";
#ifdef PLATFORM_JETSON
pipeline << "nvv4l2decoder enable-max-performancegst=1 \
! nvvidconv ! video/x-raw,format=(string)BGRx"
<< ",width=(int)" << this->getW()
<< ",height=(int)" << this->getH();
#else
pipeline << "avdec_h264 ! videoscale ! video/x-raw"
<< ",width=(int)" << this->getW()
<< ",height=(int)" << this->getH();
#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,85 @@
/*
* @Description:
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 17:57:02
* @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:57:07
* @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 17:57:30
* @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 17:56:34
* @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:
* @Author: L LC @amov
* @Date: 2023-12-19 18:30:17
* @LastEditors: L LC @amov
* @LastEditTime: 2023-12-21 17:57:12
* @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 17:57:22
* @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;
}

192
video_io/sv_camera.cpp Normal file
View File

@ -0,0 +1,192 @@
#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, 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)
{
std::map<sv::CameraType, cameraCreat>::iterator temp = svCameraList.find(type);
if (temp != svCameraList.end())
{
return temp->second(timeOut);
}
return nullptr;
}
sv::Camera::Camera(CameraType type, int timeOut)
{
this->dev = svCreatCamera(type, timeOut);
}
sv::Camera::~Camera()
{
// 休眠50ms 以便能退出线程
std::this_thread::sleep_for(std::chrono::milliseconds(50));
delete (sv_p::CameraBase *)dev;
}
sv_p::CameraBase::~CameraBase()
{
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
readThreadHandle = readThreadHandle == 0 ? 0 : pthread_cancel(readThreadHandle);
release();
}
bool sv::Camera::setStream(const std::string &ip, int port)
{
return ((sv_p::CameraBase *)dev)->setStream(ip, port);
}
bool sv::Camera::setName(const std::string &name)
{
return ((sv_p::CameraBase *)dev)->setName(name);
}
bool sv::Camera::setIndex(int index)
{
return ((sv_p::CameraBase *)dev)->setIndex(index);
}
bool sv::Camera::open(void)
{
return ((sv_p::CameraBase *)dev)->open();
}
bool sv::Camera::read(cv::Mat &image)
{
return ((sv_p::CameraBase *)dev)->read(image);
}
bool sv::Camera::readNoBlock(cv::Mat &image)
{
return ((sv_p::CameraBase *)dev)->readNoBlock(image);
}
void sv::Camera::release(void)
{
((sv_p::CameraBase *)dev)->release();
}
void sv::Camera::setWH(int width, int height)
{
((sv_p::CameraBase *)dev)->setWH(width, height);
}
void sv::Camera::setFps(int fps)
{
((sv_p::CameraBase *)dev)->setFps(fps);
}
void sv::Camera::setBrightness(double brightness)
{
((sv_p::CameraBase *)dev)->setBrightness(brightness);
}
void sv::Camera::setContrast(double contrast)
{
((sv_p::CameraBase *)dev)->setContrast(contrast);
}
void sv::Camera::setSaturation(double saturation)
{
((sv_p::CameraBase *)dev)->setSaturation(saturation);
}
void sv::Camera::setHue(double hue)
{
((sv_p::CameraBase *)dev)->setHue(hue);
}
void sv::Camera::setExposure(double exposure)
{
((sv_p::CameraBase *)dev)->setExposure(exposure);
}
bool sv::Camera::isActive(void)
{
return ((sv_p::CameraBase *)dev)->isActive();
}
sv::CameraType sv::Camera::getType(void)
{
return ((sv_p::CameraBase *)dev)->getType();
}
std::string sv::Camera::getName(void)
{
return ((sv_p::CameraBase *)dev)->getName();
}
int sv::Camera::getW(void)
{
return ((sv_p::CameraBase *)dev)->getW();
}
int sv::Camera::getH(void)
{
return ((sv_p::CameraBase *)dev)->getH();
}
int sv::Camera::getExpectFps(void)
{
return ((sv_p::CameraBase *)dev)->getExpectFps();
}
double sv::Camera::getFps(void)
{
return ((sv_p::CameraBase *)dev)->getFps();
}
double sv::Camera::getBrightness(void)
{
return ((sv_p::CameraBase *)dev)->getBrightness();
}
double sv::Camera::getContrast(void)
{
return ((sv_p::CameraBase *)dev)->getContrast();
}
double sv::Camera::getSaturation(void)
{
return ((sv_p::CameraBase *)dev)->getSaturation();
}
double sv::Camera::getHue(void)
{
return ((sv_p::CameraBase *)dev)->getHue();
}
double sv::Camera::getExposure(void)
{
return ((sv_p::CameraBase *)dev)->getExposure();
}

138
video_io/sv_camera_def.cpp Normal file
View File

@ -0,0 +1,138 @@
#include "sv_camera_privately.h"
#include "iostream"
sv_p::CameraBase::CameraBase(int timeOut)
{
this->_timeOut = 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();
isGot = true;
// 统计输入的瞬时帧率
this->fpsCurr = 1000.0f / count;
count = 0;
}
else
{
count++;
if (count > this->_timeOut)
{
// 超时则主动关闭相机
this->cap.release();
}
}
}
// 相机断开连接 记录事件后 退出线程
std::cout << "SpireCV (101) Camera has offline, check CAMERA!" << std::endl;
}
bool sv_p::CameraBase::read(cv::Mat &image)
{
bool ret = false;
std::lock_guard<std::mutex> locker(this->frameMutex);
if (this->frameEmpty.wait_for(this->frameMutex, std::chrono::milliseconds(this->_timeOut)) == std::cv_status::no_timeout)
{
// 获取图像
this->imageBuff.copyTo(image);
ret = true;
isGot = false;
}
return ret;
}
bool sv_p::CameraBase::readNoBlock(cv::Mat &image)
{
bool ret = false;
std::lock_guard<std::mutex> locker(this->frameMutex);
if (this->isGot)
{
// 该情况下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())
{
this->cap.release();
}
}

View File

@ -0,0 +1,83 @@
#ifndef __SV_CAMERA_PRIVATELY__
#define __SV_CAMERA_PRIVATELY__
#include "opencv2/opencv.hpp"
#include <stdint.h>
#include <thread>
#include <mutex>
#include <condition_variable>
#include "sv_camera.h"
namespace sv_p
{
class CameraBase
{
public:
// 图像的属性
int _width = 1280;
int _height = 720;
int _fps = 30;
float _brightness = -1;
float _contrast = -1;
float _saturation = -1;
float _hue = -1;
float _exposure = -1;
int _timeOut;
// 内部状态
float fpsCurr = -1;
bool isGot = false;
// 内部变量
cv::Mat imageBuff;
std::mutex frameMutex;
std::condition_variable_any frameEmpty;
std::thread::native_handle_type readThreadHandle = 0;
cv::VideoCapture cap;
// 获取图像的线程 在这个线程中查询、提取图像
virtual void readThread(void);
// 属性设置的接口
virtual void setWH(int width, int height);
// 基本属性 至少实现1个
virtual bool setStream(const std::string &ip, uint16_t port) { return false; }
virtual bool setName(const std::string &name) { return false; }
virtual bool setIndex(int index) { return false; }
// 扩展属性设置 默认调用opencv的实现
virtual void setFps(int fps);
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; }
virtual std::string getName(void) { return "\0"; };
virtual bool isActive(void) { return (readThreadHandle == 0 ? false : true); }
int getW(void) { return _width; }
int getH(void) { return _height; }
int getExpectFps(void) { return _fps; }
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;
virtual bool read(cv::Mat &image);
virtual bool readNoBlock(cv::Mat &image);
virtual void release(void);
CameraBase(int timeOut = 500);
~CameraBase();
};
}
#endif

View File

@ -969,172 +969,172 @@ void VideoWriterBase::releaseImpl()
}
CameraBase::CameraBase(CameraType type, int id)
{
this->_is_running = false;
this->_is_updated = false;
this->_type = type;
// CameraBase::CameraBase(CameraType type, int id)
// {
// this->_is_running = false;
// this->_is_updated = false;
// this->_type = type;
this->_width = -1;
this->_height = -1;
this->_fps = -1;
this->_ip = "192.168.2.64";
this->_port = -1;
this->_brightness = -1;
this->_contrast = -1;
this->_saturation = -1;
this->_hue = -1;
this->_exposure = -1;
// this->_width = -1;
// this->_height = -1;
// this->_fps = -1;
// this->_ip = "192.168.2.64";
// this->_port = -1;
// this->_brightness = -1;
// this->_contrast = -1;
// this->_saturation = -1;
// this->_hue = -1;
// this->_exposure = -1;
this->open(type, id);
}
CameraBase::~CameraBase()
{
this->_is_running = false;
// this->_tt.join();
}
void CameraBase::setWH(int width, int height)
{
this->_width = width;
this->_height = height;
}
void CameraBase::setFps(int fps)
{
this->_fps = fps;
}
void CameraBase::setIp(std::string ip)
{
this->_ip = ip;
}
void CameraBase::setPort(int port)
{
this->_port = port;
}
void CameraBase::setBrightness(double brightness)
{
this->_brightness = brightness;
}
void CameraBase::setContrast(double contrast)
{
this->_contrast = contrast;
}
void CameraBase::setSaturation(double saturation)
{
this->_saturation = saturation;
}
void CameraBase::setHue(double hue)
{
this->_hue = hue;
}
void CameraBase::setExposure(double exposure)
{
this->_exposure = exposure;
}
// this->open(type, id);
// }
// CameraBase::~CameraBase()
// {
// this->_is_running = false;
// // this->_tt.join();
// }
// void CameraBase::setWH(int width, int height)
// {
// this->_width = width;
// this->_height = height;
// }
// void CameraBase::setFps(int fps)
// {
// this->_fps = fps;
// }
// void CameraBase::setIp(std::string ip)
// {
// this->_ip = ip;
// }
// void CameraBase::setPort(int port)
// {
// this->_port = port;
// }
// void CameraBase::setBrightness(double brightness)
// {
// this->_brightness = brightness;
// }
// void CameraBase::setContrast(double contrast)
// {
// this->_contrast = contrast;
// }
// void CameraBase::setSaturation(double saturation)
// {
// this->_saturation = saturation;
// }
// void CameraBase::setHue(double hue)
// {
// this->_hue = hue;
// }
// void CameraBase::setExposure(double exposure)
// {
// this->_exposure = exposure;
// }
int CameraBase::getW()
{
return this->_width;
}
int CameraBase::getH()
{
return this->_height;
}
int CameraBase::getFps()
{
return this->_fps;
}
std::string CameraBase::getIp()
{
return this->_ip;
}
int CameraBase::getPort()
{
return this->_port;
}
double CameraBase::getBrightness()
{
return this->_brightness;
}
double CameraBase::getContrast()
{
return this->_contrast;
}
double CameraBase::getSaturation()
{
return this->_saturation;
}
double CameraBase::getHue()
{
return this->_hue;
}
double CameraBase::getExposure()
{
return this->_exposure;
}
bool CameraBase::isRunning()
{
return this->_is_running;
}
// int CameraBase::getW()
// {
// return this->_width;
// }
// int CameraBase::getH()
// {
// return this->_height;
// }
// int CameraBase::getFps()
// {
// return this->_fps;
// }
// std::string CameraBase::getIp()
// {
// return this->_ip;
// }
// int CameraBase::getPort()
// {
// return this->_port;
// }
// double CameraBase::getBrightness()
// {
// return this->_brightness;
// }
// double CameraBase::getContrast()
// {
// return this->_contrast;
// }
// double CameraBase::getSaturation()
// {
// return this->_saturation;
// }
// double CameraBase::getHue()
// {
// return this->_hue;
// }
// double CameraBase::getExposure()
// {
// return this->_exposure;
// }
// bool CameraBase::isRunning()
// {
// return this->_is_running;
// }
void CameraBase::openImpl()
{
// void CameraBase::openImpl()
// {
}
void CameraBase::open(CameraType type, int id)
{
this->_type = type;
this->_camera_id = id;
// }
// void CameraBase::open(CameraType type, int id)
// {
// this->_type = type;
// this->_camera_id = id;
openImpl();
// openImpl();
if (this->_cap.isOpened())
{
std::cout << "Camera opened!" << std::endl;
this->_is_running = true;
this->_tt = std::thread(&CameraBase::_run, this);
this->_tt.detach();
}
else if (type != CameraType::NONE)
{
std::cout << "Camera can NOT open!" << std::endl;
}
}
void CameraBase::_run()
{
while (this->_is_running && this->_cap.isOpened())
{
this->_cap >> this->_frame;
this->_is_updated = true;
std::this_thread::sleep_for(std::chrono::milliseconds(2));
}
}
bool CameraBase::read(cv::Mat& image)
{
if (this->_type != CameraType::NONE)
{
int n_try = 0;
while (n_try < 5000)
{
if (this->_is_updated)
{
this->_is_updated = false;
this->_frame.copyTo(image);
break;
}
std::this_thread::sleep_for(std::chrono::milliseconds(20));
n_try ++;
}
}
if (image.cols == 0 || image.rows == 0)
{
throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");
}
return image.cols > 0 && image.rows > 0;
}
void CameraBase::release()
{
_cap.release();
}
// if (this->_cap.isOpened())
// {
// std::cout << "Camera opened!" << std::endl;
// this->_is_running = true;
// this->_tt = std::thread(&CameraBase::_run, this);
// this->_tt.detach();
// }
// else if (type != CameraType::NONE)
// {
// std::cout << "Camera can NOT open!" << std::endl;
// }
// }
// void CameraBase::_run()
// {
// while (this->_is_running && this->_cap.isOpened())
// {
// this->_cap >> this->_frame;
// this->_is_updated = true;
// std::this_thread::sleep_for(std::chrono::milliseconds(2));
// }
// }
// bool CameraBase::read(cv::Mat& image)
// {
// if (this->_type != CameraType::NONE)
// {
// int n_try = 0;
// while (n_try < 5000)
// {
// if (this->_is_updated)
// {
// this->_is_updated = false;
// this->_frame.copyTo(image);
// break;
// }
// std::this_thread::sleep_for(std::chrono::milliseconds(20));
// n_try ++;
// }
// }
// if (image.cols == 0 || image.rows == 0)
// {
// throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");
// }
// return image.cols > 0 && image.rows > 0;
// }
// void CameraBase::release()
// {
// _cap.release();
// }

View File

@ -1,3 +1,4 @@
#if 0
#include "sv_video_input.h"
#include <cmath>
#include <fstream>
@ -130,3 +131,5 @@ void Camera::openImpl()
}
}
#endif