merge master
This commit is contained in:
commit
36fc8eefef
|
@ -312,7 +312,7 @@ if(USE_CUDA)
|
||||||
RUNTIME DESTINATION bin
|
RUNTIME DESTINATION bin
|
||||||
)
|
)
|
||||||
elseif(PLATFORM STREQUAL "X86_INTEL")
|
elseif(PLATFORM STREQUAL "X86_INTEL")
|
||||||
install(TARGETS sv_world
|
install(TARGETS sv_gimbal sv_world
|
||||||
LIBRARY DESTINATION lib
|
LIBRARY DESTINATION lib
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
|
@ -17,7 +17,9 @@ namespace sv
|
||||||
|
|
||||||
VeriDetector::VeriDetector()
|
VeriDetector::VeriDetector()
|
||||||
{
|
{
|
||||||
|
#ifdef WITH_CUDA
|
||||||
this->_cuda_impl = new VeriDetectorCUDAImpl;
|
this->_cuda_impl = new VeriDetectorCUDAImpl;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
VeriDetector::~VeriDetector()
|
VeriDetector::~VeriDetector()
|
||||||
{
|
{
|
||||||
|
@ -96,7 +98,7 @@ namespace sv
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
std::vector<float> output_labels;
|
std::vector<float> output_labels;
|
||||||
roiCNN(input_rois_, output_labels);
|
roiCNN(input_rois_, output_labels);
|
||||||
#endif
|
|
||||||
// auto t1 = std::chrono::system_clock::now();
|
// auto t1 = std::chrono::system_clock::now();
|
||||||
// tgts_.setFPS(1000.0 / std::chrono::duration_cast<std::chrono::milliseconds>(t1 - this->_t0).count());
|
// tgts_.setFPS(1000.0 / std::chrono::duration_cast<std::chrono::milliseconds>(t1 - this->_t0).count());
|
||||||
// this->_t0 = std::chrono::system_clock::now();
|
// this->_t0 = std::chrono::system_clock::now();
|
||||||
|
@ -108,6 +110,7 @@ namespace sv
|
||||||
tgt.sim_score = output_labels[1];
|
tgt.sim_score = output_labels[1];
|
||||||
// tgts_.targets.push_back(tgt);
|
// tgts_.targets.push_back(tgt);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void VeriDetector::getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz)
|
void VeriDetector::getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz)
|
||||||
|
|
|
@ -1,9 +1,17 @@
|
||||||
#!/bin/bash -e
|
#!/bin/bash -e
|
||||||
|
###
|
||||||
|
# @Description:
|
||||||
|
# @Author: L LC @amov
|
||||||
|
# @Date: 2023-11-21 16:10:38
|
||||||
|
# @LastEditors: L LC @amov
|
||||||
|
# @LastEditTime: 2023-11-28 11:27:13
|
||||||
|
# @FilePath: /SpireCV/build_on_x86_cuda.sh
|
||||||
|
###
|
||||||
|
|
||||||
rm -rf build
|
rm -rf build
|
||||||
mkdir build
|
mkdir build
|
||||||
cd build
|
cd build
|
||||||
cmake .. -DPLATFORM=X86_CUDA
|
cmake .. -DPLATFORM=X86_CUDA
|
||||||
make -j
|
make -j4
|
||||||
sudo make install
|
sudo make install
|
||||||
|
|
||||||
|
|
|
@ -326,7 +326,7 @@ protected:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
enum class CameraType {NONE, WEBCAM, G1, Q10, MIPI, GX40};
|
enum class CameraType {NONE, WEBCAM, V4L2CAM, G1, Q10, MIPI, GX40};
|
||||||
|
|
||||||
class CameraBase {
|
class CameraBase {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -54,7 +54,7 @@ void gimbalNoTrack(void)
|
||||||
int main(int argc, char *argv[])
|
int main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
// 实例化吊舱
|
// 实例化吊舱
|
||||||
gimbal = new sv::Gimbal(sv::GimbalType::GX40, sv::GimbalLink::SERIAL);
|
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
|
||||||
// 使用 /dev/ttyUSB0 作为控制串口
|
// 使用 /dev/ttyUSB0 作为控制串口
|
||||||
gimbal->setSerialPort("/dev/ttyUSB0");
|
gimbal->setSerialPort("/dev/ttyUSB0");
|
||||||
// 以GimableCallback作为状态回调函数启用吊舱控制
|
// 以GimableCallback作为状态回调函数启用吊舱控制
|
||||||
|
@ -62,13 +62,13 @@ int main(int argc, char *argv[])
|
||||||
// 定义相机
|
// 定义相机
|
||||||
sv::Camera cap;
|
sv::Camera cap;
|
||||||
// 设置相机流媒体地址为 192.168.2.64
|
// 设置相机流媒体地址为 192.168.2.64
|
||||||
cap.setIp("192.168.144.108");
|
cap.setIp("192.168.2.64");
|
||||||
// 设置获取画面分辨率为720P
|
// 设置获取画面分辨率为720P
|
||||||
cap.setWH(1280, 720);
|
cap.setWH(1280, 720);
|
||||||
// 设置视频帧率为30帧
|
// 设置视频帧率为30帧
|
||||||
cap.setFps(30);
|
cap.setFps(30);
|
||||||
// 开启相机
|
// 开启相机
|
||||||
cap.open(sv::CameraType::GX40);
|
cap.open(sv::CameraType::G1);
|
||||||
|
|
||||||
// 定义一个新的窗口,可在上面进行框选操作
|
// 定义一个新的窗口,可在上面进行框选操作
|
||||||
cv::namedWindow(RGB_WINDOW);
|
cv::namedWindow(RGB_WINDOW);
|
||||||
|
|
|
@ -14,14 +14,14 @@ void gimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang
|
||||||
static int count = 0;
|
static int count = 0;
|
||||||
if (count == 25)
|
if (count == 25)
|
||||||
{
|
{
|
||||||
// std::cout << "GIMBAL_CMD_RCV_POS" << std::endl;
|
std::cout << "GIMBAL_CMD_RCV_POS" << std::endl;
|
||||||
// std::cout << "=============================================" << std::endl;
|
std::cout << "=============================================" << std::endl;
|
||||||
// std::cout << "HALL_yaw:" << frame_ang_y << " " << std::endl;
|
std::cout << "HALL_yaw:" << frame_ang_y << " " << std::endl;
|
||||||
// std::cout << "HALL_roll:" << frame_ang_r << " " << std::endl;
|
std::cout << "HALL_roll:" << frame_ang_r << " " << std::endl;
|
||||||
// std::cout << "HALL_pitch:" << frame_ang_p << " " << std::endl;
|
std::cout << "HALL_pitch:" << frame_ang_p << " " << std::endl;
|
||||||
// std::cout << "GYRO_yaw:" << imu_ang_y << " " << std::endl;
|
std::cout << "GYRO_yaw:" << imu_ang_y << " " << std::endl;
|
||||||
// std::cout << "GYRO_roll:" << imu_ang_r << " " << std::endl;
|
std::cout << "GYRO_roll:" << imu_ang_r << " " << std::endl;
|
||||||
// std::cout << "GYRO_pitch:" << imu_ang_p << " " << std::endl;
|
std::cout << "GYRO_pitch:" << imu_ang_p << " " << std::endl;
|
||||||
count = 0;
|
count = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -44,7 +44,7 @@ void onMouse(int event, int x, int y, int, void *);
|
||||||
int main(int argc, char *argv[])
|
int main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
// 实例化吊舱
|
// 实例化吊舱
|
||||||
gimbal = new sv::Gimbal(sv::GimbalType::GX40, sv::GimbalLink::SERIAL);
|
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
|
||||||
// 使用 /dev/ttyUSB0 作为控制串口
|
// 使用 /dev/ttyUSB0 作为控制串口
|
||||||
gimbal->setSerialPort("/dev/ttyUSB0");
|
gimbal->setSerialPort("/dev/ttyUSB0");
|
||||||
// 以gimableCallback作为状态回调函数启用吊舱控制
|
// 以gimableCallback作为状态回调函数启用吊舱控制
|
||||||
|
@ -52,13 +52,13 @@ int main(int argc, char *argv[])
|
||||||
// 定义相机
|
// 定义相机
|
||||||
sv::Camera cap;
|
sv::Camera cap;
|
||||||
// 设置相机流媒体地址为 192.168.2.64
|
// 设置相机流媒体地址为 192.168.2.64
|
||||||
cap.setIp("192.168.144.108");
|
cap.setIp("192.168.2.64");
|
||||||
// 设置获取画面分辨率为720P
|
// 设置获取画面分辨率为720P
|
||||||
// cap.setWH(1280, 720);
|
cap.setWH(1280, 720);
|
||||||
// // 设置视频帧率为30帧
|
// // 设置视频帧率为30帧
|
||||||
// cap.setFps(30);
|
cap.setFps(30);
|
||||||
// 开启相机
|
// 开启相机
|
||||||
cap.open(sv::CameraType::GX40);
|
cap.open(sv::CameraType::G1);
|
||||||
|
|
||||||
// 定义一个窗口 才可以在上面操作
|
// 定义一个窗口 才可以在上面操作
|
||||||
cv::namedWindow(RGB_WINDOW);
|
cv::namedWindow(RGB_WINDOW);
|
||||||
|
|
|
@ -1,6 +1,5 @@
|
||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
|
|
||||||
wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
|
wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
|
||||||
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
|
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
|
||||||
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
|
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
|
||||||
|
@ -60,20 +59,9 @@ cmake -D CMAKE_BUILD_TYPE=Release \
|
||||||
-D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda \
|
-D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda \
|
||||||
-D OPENCV_ENABLE_NONFREE=ON \
|
-D OPENCV_ENABLE_NONFREE=ON \
|
||||||
-D CMAKE_INSTALL_PREFIX=/usr/local \
|
-D CMAKE_INSTALL_PREFIX=/usr/local \
|
||||||
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. \
|
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules ..
|
||||||
-D CMAKE_VERBOSE_MAKEFILE=ON \
|
|
||||||
-D ENABLE_CXX11=ON \
|
|
||||||
-D BUILD_TESTS=OFF \
|
|
||||||
-D WITH_GSTREAMER=ON \
|
|
||||||
-D OPENCV_GENERATE_PKGCONFIG=ON \
|
|
||||||
-D ENABLE_FAST_MATH=ON \
|
|
||||||
-D CUDA_FAST_MATH=ON \
|
|
||||||
-D BUILD_opencv_python3=ON \
|
|
||||||
-D PYTHON3_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.8.so \
|
|
||||||
-D PYTHON3_NUMPY_INCLUDE_DIRS=/home/aiyangsky/.local/lib/python3.8/site-packages/numpy/core/include \
|
|
||||||
-D PYTHON3_PACKAGES_PATH=/usr/lib/python3/dist-packages
|
|
||||||
|
|
||||||
make -j
|
make -j2
|
||||||
sudo make install
|
sudo make install
|
||||||
|
|
||||||
cd
|
cd
|
||||||
|
|
|
@ -58,24 +58,12 @@ sudo apt-get install -y libcurl4 build-essential pkg-config cmake libopenblas-de
|
||||||
libcanberra-gtk-module libcanberra-gtk3-module
|
libcanberra-gtk-module libcanberra-gtk3-module
|
||||||
|
|
||||||
cmake -D CMAKE_BUILD_TYPE=Release \
|
cmake -D CMAKE_BUILD_TYPE=Release \
|
||||||
-D CMAKE_VERBOSE_MAKEFILE=ON \
|
-D WITH_CUDA=OFF \
|
||||||
-D ENABLE_CXX11=ON \
|
|
||||||
-D BUILD_TESTS=OFF \
|
|
||||||
-D WITH_GSTREAMER=ON \
|
|
||||||
-D OPENCV_GENERATE_PKGCONFIG=ON \
|
|
||||||
-D ENABLE_FAST_MATH=ON \
|
|
||||||
-D CUDA_FAST_MATH=ON \
|
|
||||||
-D WITH_CUBLAS=ON \
|
|
||||||
-D WITH_CUDA=ON \
|
|
||||||
-D OPENCV_ENABLE_NONFREE=ON \
|
-D OPENCV_ENABLE_NONFREE=ON \
|
||||||
-D CMAKE_INSTALL_PREFIX=/usr/local \
|
-D CMAKE_INSTALL_PREFIX=/usr/local \
|
||||||
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. \
|
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules ..
|
||||||
-D BUILD_opencv_python3=ON \
|
|
||||||
-D PYTHON3_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.8.so \
|
|
||||||
-D PYTHON3_NUMPY_INCLUDE_DIRS=/home/aiyangsky/.local/lib/python3.8/site-packages/numpy/core/include \
|
|
||||||
-D PYTHON3_PACKAGES_PATH=/usr/lib/python3/dist-packages
|
|
||||||
|
|
||||||
make -j
|
make -j2
|
||||||
sudo make install
|
sudo make install
|
||||||
|
|
||||||
cd
|
cd
|
||||||
|
|
|
@ -1110,7 +1110,7 @@ void CameraBase::_run()
|
||||||
}
|
}
|
||||||
bool CameraBase::read(cv::Mat& image)
|
bool CameraBase::read(cv::Mat& image)
|
||||||
{
|
{
|
||||||
if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI || this->_type == CameraType::GX40)
|
if (this->_type != CameraType::NONE)
|
||||||
{
|
{
|
||||||
int n_try = 0;
|
int n_try = 0;
|
||||||
while (n_try < 5000)
|
while (n_try < 5000)
|
||||||
|
|
|
@ -5,121 +5,129 @@
|
||||||
namespace sv
|
namespace sv
|
||||||
{
|
{
|
||||||
|
|
||||||
Camera::Camera()
|
Camera::Camera()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
Camera::~Camera()
|
Camera::~Camera()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void Camera::openImpl()
|
|
||||||
|
void Camera::openImpl()
|
||||||
|
{
|
||||||
|
if (this->_type == CameraType::WEBCAM || this->_type == CameraType::V4L2CAM)
|
||||||
{
|
{
|
||||||
|
if (this->_type == CameraType::V4L2CAM)
|
||||||
|
{
|
||||||
|
this->_cap.open(this->_camera_id, cv::CAP_V4L2);
|
||||||
|
}
|
||||||
if (this->_type == CameraType::WEBCAM)
|
if (this->_type == CameraType::WEBCAM)
|
||||||
{
|
{
|
||||||
this->_cap.open(this->_camera_id);
|
this->_cap.open(this->_camera_id);
|
||||||
if (this->_width > 0 && this->_height > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width);
|
|
||||||
this->_cap.set(cv::CAP_PROP_FRAME_HEIGHT, this->_height);
|
|
||||||
}
|
|
||||||
if (this->_fps > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_FPS, this->_fps);
|
|
||||||
}
|
|
||||||
if (this->_brightness > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_BRIGHTNESS, this->_brightness);
|
|
||||||
}
|
|
||||||
if (this->_contrast > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_CONTRAST, this->_contrast);
|
|
||||||
}
|
|
||||||
if (this->_saturation > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_SATURATION, this->_saturation);
|
|
||||||
}
|
|
||||||
if (this->_hue > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_HUE, this->_hue);
|
|
||||||
}
|
|
||||||
if (this->_exposure > 0)
|
|
||||||
{
|
|
||||||
this->_cap.set(cv::CAP_PROP_EXPOSURE, this->_exposure);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
else if (this->_type == CameraType::G1)
|
if (this->_width > 0 && this->_height > 0)
|
||||||
{
|
{
|
||||||
char pipe[512];
|
this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width);
|
||||||
if (this->_width <= 0 || this->_height <= 0)
|
this->_cap.set(cv::CAP_PROP_FRAME_HEIGHT, this->_height);
|
||||||
{
|
|
||||||
this->_width = 1280;
|
|
||||||
this->_height = 720;
|
|
||||||
}
|
|
||||||
if (this->_port <= 0)
|
|
||||||
{
|
|
||||||
this->_port = 554;
|
|
||||||
}
|
|
||||||
if (this->_fps <= 0)
|
|
||||||
{
|
|
||||||
this->_fps = 30;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef PLATFORM_X86_CUDA
|
|
||||||
sprintf(pipe, "rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
|
|
||||||
this->_cap.open(pipe);
|
|
||||||
#endif
|
|
||||||
#ifdef PLATFORM_JETSON
|
|
||||||
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
|
|
||||||
this->_cap.open(pipe, cv::CAP_GSTREAMER);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
else if (this->_type == CameraType::GX40)
|
if (this->_fps > 0)
|
||||||
{
|
{
|
||||||
std::ostringstream camera_url;
|
this->_cap.set(cv::CAP_PROP_FPS, this->_fps);
|
||||||
if (this->_width <= 0 || this->_height <= 0)
|
|
||||||
{
|
|
||||||
this->_width = 1280;
|
|
||||||
this->_height = 720;
|
|
||||||
}
|
|
||||||
if (this->_port <= 0)
|
|
||||||
{
|
|
||||||
this->_port = 554;
|
|
||||||
}
|
|
||||||
#ifdef PLATFORM_X86_CUDA
|
|
||||||
camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
|
|
||||||
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! application/x-rtp,media=video ! \
|
|
||||||
rtph265depay ! parsebin ! avdec_h265 ! videoscale ! video/x-raw,width=(int)" << this->_width
|
|
||||||
<< ",height=(int)" << this->_height << " ! videoflip video-direction=4 ! videoconvert ! video/x-raw,format=(string)BGR ! \
|
|
||||||
appsink sync=false";
|
|
||||||
this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER);
|
|
||||||
#endif
|
|
||||||
#ifdef PLATFORM_JETSON
|
|
||||||
camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
|
|
||||||
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! \
|
|
||||||
application/x-rtp,media=video ! rtph265depay ! parsebin ! \
|
|
||||||
nvv4l2decoder ! nvvidconv flip-method=4 ! \
|
|
||||||
video/x-raw,format=(string)BGRx,width=(int)"
|
|
||||||
<< this->_width << ",height=(int)" << this->_height << " ! videoconvert ! video/x-raw,format=(string)BGR ! \
|
|
||||||
appsink sync=false";
|
|
||||||
this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
else if (this->_type == CameraType::MIPI)
|
if (this->_brightness > 0)
|
||||||
{
|
{
|
||||||
char pipe[512];
|
this->_cap.set(cv::CAP_PROP_BRIGHTNESS, this->_brightness);
|
||||||
if (this->_width <= 0 || this->_height <= 0)
|
}
|
||||||
{
|
if (this->_contrast > 0)
|
||||||
this->_width = 1280;
|
{
|
||||||
this->_height = 720;
|
this->_cap.set(cv::CAP_PROP_CONTRAST, this->_contrast);
|
||||||
}
|
}
|
||||||
if (this->_fps <= 0)
|
if (this->_saturation > 0)
|
||||||
{
|
{
|
||||||
this->_fps = 30;
|
this->_cap.set(cv::CAP_PROP_SATURATION, this->_saturation);
|
||||||
}
|
}
|
||||||
|
if (this->_hue > 0)
|
||||||
sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height);
|
{
|
||||||
this->_cap.open(pipe, cv::CAP_GSTREAMER);
|
this->_cap.set(cv::CAP_PROP_HUE, this->_hue);
|
||||||
|
}
|
||||||
|
if (this->_exposure > 0)
|
||||||
|
{
|
||||||
|
this->_cap.set(cv::CAP_PROP_EXPOSURE, this->_exposure);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
else if (this->_type == CameraType::G1)
|
||||||
|
{
|
||||||
|
char pipe[512];
|
||||||
|
if (this->_width <= 0 || this->_height <= 0)
|
||||||
|
{
|
||||||
|
this->_width = 1280;
|
||||||
|
this->_height = 720;
|
||||||
|
}
|
||||||
|
if (this->_port <= 0)
|
||||||
|
{
|
||||||
|
this->_port = 554;
|
||||||
|
}
|
||||||
|
if (this->_fps <= 0)
|
||||||
|
{
|
||||||
|
this->_fps = 30;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef PLATFORM_X86_CUDA
|
||||||
|
sprintf(pipe, "rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
|
||||||
|
this->_cap.open(pipe);
|
||||||
|
#endif
|
||||||
|
#ifdef PLATFORM_JETSON
|
||||||
|
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
|
||||||
|
this->_cap.open(pipe, cv::CAP_GSTREAMER);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else if (this->_type == CameraType::GX40)
|
||||||
|
{
|
||||||
|
std::ostringstream camera_url;
|
||||||
|
if (this->_width <= 0 || this->_height <= 0)
|
||||||
|
{
|
||||||
|
this->_width = 1280;
|
||||||
|
this->_height = 720;
|
||||||
|
}
|
||||||
|
if (this->_port <= 0)
|
||||||
|
{
|
||||||
|
this->_port = 554;
|
||||||
|
}
|
||||||
|
#ifdef PLATFORM_X86_CUDA
|
||||||
|
camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
|
||||||
|
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! application/x-rtp,media=video ! \
|
||||||
|
rtph265depay ! parsebin ! avdec_h265 ! videoscale ! video/x-raw,width=(int)" << this->_width
|
||||||
|
<< ",height=(int)" << this->_height << " ! videoflip video-direction=4 ! videoconvert ! video/x-raw,format=(string)BGR ! \
|
||||||
|
appsink sync=false";
|
||||||
|
this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER);
|
||||||
|
#endif
|
||||||
|
#ifdef PLATFORM_JETSON
|
||||||
|
camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
|
||||||
|
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! \
|
||||||
|
application/x-rtp,media=video ! rtph265depay ! parsebin ! \
|
||||||
|
nvv4l2decoder ! nvvidconv flip-method=4 ! \
|
||||||
|
video/x-raw,format=(string)BGRx,width=(int)"
|
||||||
|
<< this->_width << ",height=(int)" << this->_height << " ! videoconvert ! video/x-raw,format=(string)BGR ! \
|
||||||
|
appsink sync=false";
|
||||||
|
this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else if (this->_type == CameraType::MIPI)
|
||||||
|
{
|
||||||
|
char pipe[512];
|
||||||
|
if (this->_width <= 0 || this->_height <= 0)
|
||||||
|
{
|
||||||
|
this->_width = 1280;
|
||||||
|
this->_height = 720;
|
||||||
|
}
|
||||||
|
if (this->_fps <= 0)
|
||||||
|
{
|
||||||
|
this->_fps = 30;
|
||||||
|
}
|
||||||
|
|
||||||
|
sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height);
|
||||||
|
this->_cap.open(pipe, cv::CAP_GSTREAMER);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue