forked from floratest1/SpireCV
Compare commits
33 Commits
v0.1.1
...
rewrite-ca
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
fe18e3e0b6 | ||
|
|
5d2e5b0250 | ||
|
|
9f35bf476e | ||
|
|
173acc7036 | ||
|
|
a0d3e258d9 | ||
|
|
dd3216e19e | ||
|
|
e5c00087ed | ||
|
|
ad7cabe238 | ||
|
|
c23d947661 | ||
|
|
9cc0f44573 | ||
|
|
493c40fb73 | ||
|
|
43deec9daa | ||
|
|
05538095e3 | ||
|
|
ec7f7f7454 | ||
|
|
7b2fe3a3b5 | ||
|
|
c81716302d | ||
|
|
62051a730b | ||
|
|
ad54f95313 | ||
|
|
02bca32ea4 | ||
|
|
6c417adc34 | ||
|
|
315c63a472 | ||
|
|
dbd60027ef | ||
|
|
2985661e90 | ||
|
|
4ec37d79e3 | ||
|
|
831eab5197 | ||
|
|
469ba77fe6 | ||
|
|
36fc8eefef | ||
|
|
4e4a479b08 | ||
|
|
ae21d40e2b | ||
|
|
e46c02cdf7 | ||
|
|
169f4ba55b | ||
|
|
6cf8422835 | ||
|
|
dc0d10137d |
@@ -69,6 +69,7 @@ include_directories(
|
|||||||
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/G1
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/G1
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/AT10
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/AT10
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/Q10f
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/Q10f
|
||||||
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/GX40
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl
|
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/common_det/cuda
|
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/common_det/cuda
|
||||||
@@ -76,7 +77,7 @@ include_directories(
|
|||||||
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/sot/ocv470
|
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/sot/ocv470
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/color_line
|
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/color_line
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/video_io
|
${CMAKE_CURRENT_SOURCE_DIR}/video_io
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/veri/cuda
|
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/veri/cuda
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/ellipse_det
|
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/ellipse_det
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}/utils
|
${CMAKE_CURRENT_SOURCE_DIR}/utils
|
||||||
)
|
)
|
||||||
@@ -118,7 +119,8 @@ set(
|
|||||||
include/sv_mot.h
|
include/sv_mot.h
|
||||||
include/sv_color_line.h
|
include/sv_color_line.h
|
||||||
include/sv_veri_det.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_video_output.h
|
||||||
include/sv_world.h
|
include/sv_world.h
|
||||||
)
|
)
|
||||||
@@ -139,6 +141,8 @@ file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/AT10/
|
|||||||
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
||||||
file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/Q10f/*.cpp)
|
file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/Q10f/*.cpp)
|
||||||
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
||||||
|
file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/GX40/*.cpp)
|
||||||
|
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
||||||
file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/*.cpp)
|
file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/*.cpp)
|
||||||
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
list(APPEND driver_SRCS ${DRV_LIB_FILES})
|
||||||
|
|
||||||
@@ -290,7 +294,9 @@ target_link_libraries(EvalModelOnCocoVal sv_world)
|
|||||||
|
|
||||||
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/samples/calib)
|
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/samples/calib)
|
||||||
add_executable(CameraCalibrarion samples/calib/calibrate_camera_charuco.cpp)
|
add_executable(CameraCalibrarion samples/calib/calibrate_camera_charuco.cpp)
|
||||||
target_link_libraries(CameraCalibrarion ${OpenCV_LIBS})
|
target_link_libraries(CameraCalibrarion ${OpenCV_LIBS} sv_world)
|
||||||
|
add_executable(CreateMarker samples/calib/create_marker.cpp)
|
||||||
|
target_link_libraries(CreateMarker ${OpenCV_LIBS})
|
||||||
|
|
||||||
message(STATUS "CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}")
|
message(STATUS "CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}")
|
||||||
if (NOT DEFINED SV_INSTALL_PREFIX)
|
if (NOT DEFINED SV_INSTALL_PREFIX)
|
||||||
@@ -309,7 +315,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()
|
||||||
|
|||||||
@@ -12,7 +12,7 @@ SpireCV是一个专为**智能无人系统**打造的**边缘实时感知SDK**
|
|||||||
|
|
||||||
## 快速入门
|
## 快速入门
|
||||||
|
|
||||||
- 安装及使用:[SpireCV使用手册](https://docs.amovlab.com/Spire_CV_Amov/#/)、[SpireCV开发者套件指南](https://docs.amovlab.com/spirecvkit/#/)
|
- 安装及使用:[SpireCV使用手册](https://docs.amovlab.com/Spire_CV_Amov/#/)([wolai版本](https://www.wolai.com/4qWFM6aZmtpQE6jj7hnNMW))、[SpireCV开发者套件指南](https://docs.amovlab.com/spirecvkit/#/)
|
||||||
- 需掌握C++语言基础、CMake编译工具基础。
|
- 需掌握C++语言基础、CMake编译工具基础。
|
||||||
- 需要掌握OpenCV视觉库基础,了解CUDA、OpenVINO、RKNN和CANN等计算库。
|
- 需要掌握OpenCV视觉库基础,了解CUDA、OpenVINO、RKNN和CANN等计算库。
|
||||||
- 需要了解ROS基本概念及基本操作。
|
- 需要了解ROS基本概念及基本操作。
|
||||||
|
|||||||
@@ -94,7 +94,8 @@ void ArucoDetector::_load()
|
|||||||
// _detector_params = aruco::DetectorParameters::create();
|
// _detector_params = aruco::DetectorParameters::create();
|
||||||
_detector_params = new aruco::DetectorParameters;
|
_detector_params = new aruco::DetectorParameters;
|
||||||
for (auto i : aruco_params_value) {
|
for (auto i : aruco_params_value) {
|
||||||
if ("_dictionary_id" == std::string(i->key)) {
|
if ("dictionaryId" == std::string(i->key)) {
|
||||||
|
// std::cout << "dictionary_id (old, new): " << _dictionary_id << ", " << i->value.toNumber() << std::endl;
|
||||||
_dictionary_id = i->value.toNumber();
|
_dictionary_id = i->value.toNumber();
|
||||||
}
|
}
|
||||||
else if ("adaptiveThreshConstant" == std::string(i->key)) {
|
else if ("adaptiveThreshConstant" == std::string(i->key)) {
|
||||||
|
|||||||
@@ -74,10 +74,10 @@ namespace sv
|
|||||||
bool VeriDetectorCUDAImpl::cudaSetup()
|
bool VeriDetectorCUDAImpl::cudaSetup()
|
||||||
{
|
{
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
std::string trt_model_fn = get_home() + SV_MODEL_DIR + "model.engine";
|
std::string trt_model_fn = get_home() + SV_MODEL_DIR + "veri.engine";
|
||||||
if (!is_file_exist(trt_model_fn))
|
if (!is_file_exist(trt_model_fn))
|
||||||
{
|
{
|
||||||
throw std::runtime_error("SpireCV (104) Error loading the VERI TensorRT model (File Not Exist)");
|
throw std::runtime_error("SpireCV (104) Error loading the VeriDetector TensorRT model (File Not Exist)");
|
||||||
}
|
}
|
||||||
char *trt_model_stream{nullptr};
|
char *trt_model_stream{nullptr};
|
||||||
size_t trt_model_size{0};
|
size_t trt_model_size{0};
|
||||||
@@ -107,7 +107,7 @@ namespace sv
|
|||||||
|
|
||||||
delete[] trt_model_stream;
|
delete[] trt_model_stream;
|
||||||
const ICudaEngine &cu_engine = this->_trt_context->getEngine();
|
const ICudaEngine &cu_engine = this->_trt_context->getEngine();
|
||||||
assert(cu_engine.getNbBindings() == 2);
|
assert(cu_engine.getNbBindings() == 3);
|
||||||
|
|
||||||
this->_input_index = cu_engine.getBindingIndex("input");
|
this->_input_index = cu_engine.getBindingIndex("input");
|
||||||
this->_output_index1 = cu_engine.getBindingIndex("output");
|
this->_output_index1 = cu_engine.getBindingIndex("output");
|
||||||
@@ -123,7 +123,6 @@ namespace sv
|
|||||||
this->_p_data = new float[2 * 3 * 224 * 224];
|
this->_p_data = new float[2 * 3 * 224 * 224];
|
||||||
this->_p_prob1 = new float[2 * 576];
|
this->_p_prob1 = new float[2 * 576];
|
||||||
this->_p_prob2 = new float[2 * 1280];
|
this->_p_prob2 = new float[2 * 1280];
|
||||||
this->_p_prob3 = new float[2 * 1280];
|
|
||||||
// Input
|
// Input
|
||||||
TRTCHECK(cudaMemcpyAsync(_p_buffers[this->_input_index], this->_p_data, 2 * 3 * 224 * 224 * sizeof(float), cudaMemcpyHostToDevice, this->_cu_stream));
|
TRTCHECK(cudaMemcpyAsync(_p_buffers[this->_input_index], this->_p_data, 2 * 3 * 224 * 224 * sizeof(float), cudaMemcpyHostToDevice, this->_cu_stream));
|
||||||
// this->_trt_context->enqueue(1, _p_buffers, this->_cu_stream, nullptr);
|
// this->_trt_context->enqueue(1, _p_buffers, this->_cu_stream, nullptr);
|
||||||
@@ -139,11 +138,12 @@ namespace sv
|
|||||||
|
|
||||||
void VeriDetectorCUDAImpl::cudaRoiCNN(
|
void VeriDetectorCUDAImpl::cudaRoiCNN(
|
||||||
std::vector<cv::Mat> &input_rois_,
|
std::vector<cv::Mat> &input_rois_,
|
||||||
std::vector<int> &output_labels_)
|
std::vector<float> &output_labels_)
|
||||||
{
|
{
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
|
|
||||||
for (int i = 0; i < 2; ++i)
|
|
||||||
|
for (int i = 0; i < 2; i++)
|
||||||
{
|
{
|
||||||
for (int row = 0; row < 224; ++row)
|
for (int row = 0; row < 224; ++row)
|
||||||
{
|
{
|
||||||
@@ -151,14 +151,15 @@ namespace sv
|
|||||||
for (int col = 0; col < 224; ++col)
|
for (int col = 0; col < 224; ++col)
|
||||||
{
|
{
|
||||||
// mean=[136.20, 141.50, 145.41], std=[44.77, 44.20, 44.30]
|
// mean=[136.20, 141.50, 145.41], std=[44.77, 44.20, 44.30]
|
||||||
this->_p_data[224 * 224 * 3 * i + col + row * 224] = ((float)uc_pixel[0] - 136.20f) / 44.77f;
|
this->_p_data[col + row * 224 + 224 * 224 * 3 * i] = ((float)uc_pixel[0] - 136.20f) / 44.77f;
|
||||||
this->_p_data[224 * 224 * 3 * i + col + row * 224 + 224 * 224] = ((float)uc_pixel[1] - 141.50f) / 44.20f;
|
this->_p_data[col + row * 224 + 224 * 224 + 224 * 224 * 3 * i] = ((float)uc_pixel[1] - 141.50f) / 44.20f;
|
||||||
this->_p_data[224 * 224 * 3 * i + col + row * 224 + 224 * 224 * 2] = ((float)uc_pixel[2] - 145.41f) / 44.30f;
|
this->_p_data[col + row * 224 + 224 * 224 * 2 + 224 * 224 * 3 * i] = ((float)uc_pixel[2] - 145.41f) / 44.30f;
|
||||||
uc_pixel += 3;
|
uc_pixel += 3;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Input
|
// Input
|
||||||
TRTCHECK(cudaMemcpyAsync(_p_buffers[this->_input_index], this->_p_data, 2 * 3 * 224 * 224 * sizeof(float), cudaMemcpyHostToDevice, this->_cu_stream));
|
TRTCHECK(cudaMemcpyAsync(_p_buffers[this->_input_index], this->_p_data, 2 * 3 * 224 * 224 * sizeof(float), cudaMemcpyHostToDevice, this->_cu_stream));
|
||||||
// this->_trt_context->enqueue(1, _p_buffers, this->_cu_stream, nullptr);
|
// this->_trt_context->enqueue(1, _p_buffers, this->_cu_stream, nullptr);
|
||||||
@@ -180,10 +181,9 @@ namespace sv
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// 计算两个数组的余弦相似性
|
float similarity = cosineSimilarity(this->_p_prob2, this->_p_prob2 + 1280, 1280);
|
||||||
float similarity = cosineSimilarity(_p_prob2, _p_prob2 + 1280, 1280);
|
output_labels_.push_back(label);
|
||||||
std::cout << "余弦相似性: " << similarity << std::endl;
|
output_labels_.push_back(similarity);
|
||||||
std::cout << "VERI LABEL: " << label << std::endl;
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -29,14 +29,13 @@ public:
|
|||||||
bool cudaSetup();
|
bool cudaSetup();
|
||||||
void cudaRoiCNN(
|
void cudaRoiCNN(
|
||||||
std::vector<cv::Mat>& input_rois_,
|
std::vector<cv::Mat>& input_rois_,
|
||||||
std::vector<int>& output_labels_
|
std::vector<float>& output_labels_
|
||||||
);
|
);
|
||||||
|
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
float *_p_data;
|
float *_p_data;
|
||||||
float *_p_prob1;
|
float *_p_prob1;
|
||||||
float *_p_prob2;
|
float *_p_prob2;
|
||||||
float *_p_prob3;
|
|
||||||
nvinfer1::IExecutionContext *_trt_context;
|
nvinfer1::IExecutionContext *_trt_context;
|
||||||
int _input_index;
|
int _input_index;
|
||||||
int _output_index1;
|
int _output_index1;
|
||||||
|
|||||||
@@ -1,61 +1,153 @@
|
|||||||
#include "sv_veri_det.h"
|
#include "sv_veri_det.h"
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
#include "gason.h"
|
||||||
|
#include "sv_util.h"
|
||||||
|
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
#include <NvInfer.h>
|
#include <NvInfer.h>
|
||||||
#include <cuda_runtime_api.h>
|
#include <cuda_runtime_api.h>
|
||||||
#include "veri_det_cuda_impl.h"
|
#include "veri_det_cuda_impl.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define SV_ROOT_DIR "/SpireCV/"
|
||||||
|
|
||||||
namespace sv {
|
namespace sv
|
||||||
|
|
||||||
|
|
||||||
VeriDetector::VeriDetector()
|
|
||||||
{
|
{
|
||||||
this->_cuda_impl = new VeriDetectorCUDAImpl;
|
|
||||||
}
|
|
||||||
VeriDetector::~VeriDetector()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
bool VeriDetector::setupImpl()
|
VeriDetector::VeriDetector()
|
||||||
{
|
{
|
||||||
#ifdef WITH_CUDA
|
#ifdef WITH_CUDA
|
||||||
return this->_cuda_impl->cudaSetup();
|
this->_cuda_impl = new VeriDetectorCUDAImpl;
|
||||||
#endif
|
#endif
|
||||||
return false;
|
}
|
||||||
}
|
VeriDetector::~VeriDetector()
|
||||||
|
|
||||||
void VeriDetector::roiCNN(
|
|
||||||
std::vector<cv::Mat>& input_rois_,
|
|
||||||
std::vector<int>& output_labels_
|
|
||||||
)
|
|
||||||
{
|
|
||||||
#ifdef WITH_CUDA
|
|
||||||
this->_cuda_impl->cudaRoiCNN(
|
|
||||||
input_rois_,
|
|
||||||
output_labels_
|
|
||||||
);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void VeriDetector::detect(cv::Mat img1_, cv::Mat img2_, TargetsInFrame& tgts_)
|
|
||||||
{
|
|
||||||
if (!_params_loaded)
|
|
||||||
{
|
{
|
||||||
this->_load();
|
|
||||||
this->_loadLabels();
|
|
||||||
_params_loaded = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
std::vector<cv::Mat> e_roi = {img1_, img2_};
|
void VeriDetector::_load()
|
||||||
|
{
|
||||||
|
JsonValue all_value;
|
||||||
|
JsonAllocator allocator;
|
||||||
|
_load_all_json(this->alg_params_fn, all_value, allocator);
|
||||||
|
|
||||||
std::vector<int> output_labels;
|
JsonValue veriliner_params_value;
|
||||||
roiCNN(e_roi, output_labels);
|
_parser_algorithm_params("VeriDetector", all_value, veriliner_params_value);
|
||||||
}
|
|
||||||
|
for (auto i : veriliner_params_value)
|
||||||
|
{
|
||||||
|
if ("vehicle_ID" == std::string(i->key))
|
||||||
|
{
|
||||||
|
this->vehicle_id = i->value.toString();
|
||||||
|
std::cout << "vehicle_ID Load Sucess!" << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool VeriDetector::setupImpl()
|
||||||
|
{
|
||||||
|
#ifdef WITH_CUDA
|
||||||
|
return this->_cuda_impl->cudaSetup();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void VeriDetector::roiCNN(
|
||||||
|
std::vector<cv::Mat> &input_rois_,
|
||||||
|
std::vector<float> &output_labels_)
|
||||||
|
{
|
||||||
|
#ifdef WITH_CUDA
|
||||||
|
this->_cuda_impl->cudaRoiCNN(
|
||||||
|
input_rois_,
|
||||||
|
output_labels_);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void VeriDetector::detect(cv::Mat img_, const cv::Rect &bounding_box_, sv::Target &tgt)
|
||||||
|
{
|
||||||
|
if (!_params_loaded)
|
||||||
|
{
|
||||||
|
this->_load();
|
||||||
|
this->_loadLabels();
|
||||||
|
_params_loaded = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// convert Rect2d from left-up to center.
|
||||||
|
targetPos[0] = float(bounding_box_.x) + float(bounding_box_.width) * 0.5f;
|
||||||
|
targetPos[1] = float(bounding_box_.y) + float(bounding_box_.height) * 0.5f;
|
||||||
|
|
||||||
|
targetSz[0] = float(bounding_box_.width);
|
||||||
|
targetSz[1] = float(bounding_box_.height);
|
||||||
|
|
||||||
|
// Extent the bounding box.
|
||||||
|
float sumSz = targetSz[0] + targetSz[1];
|
||||||
|
float wExtent = targetSz[0] + 0.5 * (sumSz);
|
||||||
|
float hExtent = targetSz[1] + 0.5 * (sumSz);
|
||||||
|
int sz = int(cv::sqrt(wExtent * hExtent));
|
||||||
|
|
||||||
|
cv::Mat crop;
|
||||||
|
getSubwindow(crop, img_, sz, 224);
|
||||||
|
|
||||||
|
std::string img_ground_dir = get_home() + SV_ROOT_DIR + this->vehicle_id;
|
||||||
|
cv::Mat img_ground = cv::imread(img_ground_dir);
|
||||||
|
cv::resize(img_ground, img_ground, cv::Size(224, 224));
|
||||||
|
std::vector<cv::Mat> input_rois_ = {crop, img_ground};
|
||||||
|
|
||||||
|
#ifdef WITH_CUDA
|
||||||
|
std::vector<float> output_labels;
|
||||||
|
roiCNN(input_rois_, output_labels);
|
||||||
|
|
||||||
|
// auto t1 = std::chrono::system_clock::now();
|
||||||
|
// tgts_.setFPS(1000.0 / std::chrono::duration_cast<std::chrono::milliseconds>(t1 - this->_t0).count());
|
||||||
|
// this->_t0 = std::chrono::system_clock::now();
|
||||||
|
// tgts_.setTimeNow();
|
||||||
|
|
||||||
|
if (output_labels.size() > 0)
|
||||||
|
{
|
||||||
|
// tgt.category_id = output_labels[0];
|
||||||
|
tgt.sim_score = output_labels[1];
|
||||||
|
// tgts_.targets.push_back(tgt);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void VeriDetector::getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz)
|
||||||
|
{
|
||||||
|
cv::Scalar avgChans = mean(srcImg);
|
||||||
|
cv::Size imgSz = srcImg.size();
|
||||||
|
int c = (originalSz + 1) / 2;
|
||||||
|
|
||||||
|
int context_xmin = (int)(targetPos[0]) - c;
|
||||||
|
int context_xmax = context_xmin + originalSz - 1;
|
||||||
|
int context_ymin = (int)(targetPos[1]) - c;
|
||||||
|
int context_ymax = context_ymin + originalSz - 1;
|
||||||
|
|
||||||
|
int left_pad = std::max(0, -context_xmin);
|
||||||
|
int top_pad = std::max(0, -context_ymin);
|
||||||
|
int right_pad = std::max(0, context_xmax - imgSz.width + 1);
|
||||||
|
int bottom_pad = std::max(0, context_ymax - imgSz.height + 1);
|
||||||
|
|
||||||
|
context_xmin += left_pad;
|
||||||
|
context_xmax += left_pad;
|
||||||
|
context_ymin += top_pad;
|
||||||
|
context_ymax += top_pad;
|
||||||
|
|
||||||
|
cv::Mat cropImg;
|
||||||
|
if (left_pad == 0 && top_pad == 0 && right_pad == 0 && bottom_pad == 0)
|
||||||
|
{
|
||||||
|
// Crop image without padding.
|
||||||
|
cropImg = srcImg(cv::Rect(context_xmin, context_ymin,
|
||||||
|
context_xmax - context_xmin + 1, context_ymax - context_ymin + 1));
|
||||||
|
}
|
||||||
|
else // Crop image with padding, and the padding value is avgChans
|
||||||
|
{
|
||||||
|
cv::Mat tmpMat;
|
||||||
|
cv::copyMakeBorder(srcImg, tmpMat, top_pad, bottom_pad, left_pad, right_pad, cv::BORDER_CONSTANT, avgChans);
|
||||||
|
cropImg = tmpMat(cv::Rect(context_xmin, context_ymin, context_xmax - context_xmin + 1, context_ymax - context_ymin + 1));
|
||||||
|
}
|
||||||
|
resize(cropImg, dstCrop, cv::Size(resizeSz, resizeSz));
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-08-16 21:53:43
|
* @LastEditTime: 2023-12-05 16:30:27
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_crc32.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h
|
||||||
*/
|
*/
|
||||||
#ifndef AT10_GIMBAL_CRC32_H
|
#ifndef AT10_GIMBAL_CRC32_H
|
||||||
#define AT10_GIMBAL_CRC32_H
|
#define AT10_GIMBAL_CRC32_H
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-08-25 19:39:56
|
* @LastEditTime: 2023-12-06 10:27:59
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_driver.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp
|
||||||
*/
|
*/
|
||||||
#include "AT10_gimbal_driver.h"
|
#include "AT10_gimbal_driver.h"
|
||||||
#include "AT10_gimbal_crc32.h"
|
#include "AT10_gimbal_crc32.h"
|
||||||
@@ -24,13 +24,6 @@ AT10GimbalDriver::AT10GimbalDriver(amovGimbal::IOStreamBase *_IO) : amovGimbal::
|
|||||||
stdRxQueue = new fifoRing(sizeof(AT10::GIMBAL_STD_FRAME_T), MAX_QUEUE_SIZE);
|
stdRxQueue = new fifoRing(sizeof(AT10::GIMBAL_STD_FRAME_T), MAX_QUEUE_SIZE);
|
||||||
stdTxQueue = new fifoRing(sizeof(AT10::GIMBAL_STD_FRAME_T), MAX_QUEUE_SIZE);
|
stdTxQueue = new fifoRing(sizeof(AT10::GIMBAL_STD_FRAME_T), MAX_QUEUE_SIZE);
|
||||||
parserState = AT10::GIMBAL_SERIAL_STATE_IDLE;
|
parserState = AT10::GIMBAL_SERIAL_STATE_IDLE;
|
||||||
|
|
||||||
// Initialize and enable attitude data return (50Hz)
|
|
||||||
// uint8_t cmd = 0XFF;
|
|
||||||
// pack(AT10::GIMBAL_CMD_SET_FEEDBACK_H, &cmd, 1);
|
|
||||||
// pack(AT10::GIMBAL_CMD_SET_FEEDBACK_L, &cmd, 1);
|
|
||||||
// cmd = 0X00;
|
|
||||||
// pack(AT10::GIMBAL_CMD_OPEN_FEEDBACK, &cmd, 1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -84,21 +77,7 @@ void AT10GimbalDriver::convert(void *buf)
|
|||||||
switch (temp->head)
|
switch (temp->head)
|
||||||
{
|
{
|
||||||
case AT10::GIMBAL_CMD_RCV_STATE:
|
case AT10::GIMBAL_CMD_RCV_STATE:
|
||||||
std::cout << "Undefined old frame from AT10";
|
std::cout << "Undefined old frame from AT10\r\n";
|
||||||
// AT10::GIMBAL_RCV_POS_MSG_T *tempPos;
|
|
||||||
// tempPos = reinterpret_cast<AT10::GIMBAL_RCV_POS_MSG_T *>(((uint8_t *)buf) + AT10_EXT_PAYLOAD_OFFSET);
|
|
||||||
// mState.lock();
|
|
||||||
// state.abs.yaw = tempPos->yawIMUAngle * AT10_EXT_SCALE_FACTOR_ANGLE;
|
|
||||||
// state.abs.roll = tempPos->rollIMUAngle * AT10_EXT_SCALE_FACTOR_ANGLE;
|
|
||||||
// state.abs.pitch = tempPos->pitchIMUAngle * AT10_EXT_SCALE_FACTOR_ANGLE;
|
|
||||||
// state.rel.yaw = tempPos->yawStatorRotorAngle * AT10_EXT_SCALE_FACTOR_SPEED;
|
|
||||||
// state.rel.roll = tempPos->rollStatorRotorAngle * AT10_EXT_SCALE_FACTOR_SPEED;
|
|
||||||
// state.rel.pitch = tempPos->pitchStatorRotorAngle * AT10_EXT_SCALE_FACTOR_SPEED;
|
|
||||||
// updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
|
||||||
// state.abs.roll, state.abs.pitch, state.abs.yaw,
|
|
||||||
// state.fov.x, state.fov.y);
|
|
||||||
// mState.unlock();
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AT10::GIMBAL_CMD_STD:
|
case AT10::GIMBAL_CMD_STD:
|
||||||
@@ -123,15 +102,15 @@ void AT10GimbalDriver::convert(void *buf)
|
|||||||
state.fov.y = amovGimbalTools::conversionBigLittle(tempRcv->D1.fovY) * 0.1;
|
state.fov.y = amovGimbalTools::conversionBigLittle(tempRcv->D1.fovY) * 0.1;
|
||||||
if ((amovGimbalTools::conversionBigLittle(tempRcv->D1.camera) & 0X0003) == 0X01)
|
if ((amovGimbalTools::conversionBigLittle(tempRcv->D1.camera) & 0X0003) == 0X01)
|
||||||
{
|
{
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_TAKE;
|
state.video = AMOV_GIMBAL_VIDEO_TAKE;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_OFF;
|
state.video = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
}
|
}
|
||||||
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
||||||
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
||||||
state.fov.x, state.fov.y);
|
state.fov.x, state.fov.y, updataCaller);
|
||||||
mState.unlock();
|
mState.unlock();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@@ -316,21 +295,9 @@ bool AT10GimbalDriver::parser(IN uint8_t byte)
|
|||||||
|
|
||||||
void AT10GimbalDriver::sendHeart(void)
|
void AT10GimbalDriver::sendHeart(void)
|
||||||
{
|
{
|
||||||
// uint8_t tempBuffer[72];
|
|
||||||
uint8_t temp = 0X00;
|
uint8_t temp = 0X00;
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
// if (!IO->isBusy() && IO->isOpen())
|
|
||||||
// {
|
|
||||||
// bool state = false;
|
|
||||||
|
|
||||||
// state = txQueue->outCell(&tempBuffer);
|
|
||||||
// if (state)
|
|
||||||
// {
|
|
||||||
// IO->outPutBytes((uint8_t *)&tempBuffer,
|
|
||||||
// reinterpret_cast<AT10::GIMBAL_EXTEND_FRAME_T *>(tempBuffer)->len + AT10_EXT_PAYLOAD_OFFSET + sizeof(uint8_t));
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
pack(AT10::GIMBAL_CMD_STD_HEART, &temp, sizeof(temp));
|
pack(AT10::GIMBAL_CMD_STD_HEART, &temp, sizeof(temp));
|
||||||
}
|
}
|
||||||
@@ -363,19 +330,26 @@ void AT10GimbalDriver::stackStart(void)
|
|||||||
}
|
}
|
||||||
std::thread sendHeartLoop(&AT10GimbalDriver::sendHeart, this);
|
std::thread sendHeartLoop(&AT10GimbalDriver::sendHeart, this);
|
||||||
std::thread sendStdLoop(&AT10GimbalDriver::sendStd, this);
|
std::thread sendStdLoop(&AT10GimbalDriver::sendStd, this);
|
||||||
|
|
||||||
|
this->sendThreadHanle = sendStdLoop.native_handle();
|
||||||
|
this->sendHreatThreadHandle = sendHeartLoop.native_handle();
|
||||||
|
|
||||||
sendHeartLoop.detach();
|
sendHeartLoop.detach();
|
||||||
sendStdLoop.detach();
|
sendStdLoop.detach();
|
||||||
}
|
}
|
||||||
|
|
||||||
void AT10GimbalDriver::parserLoop(void)
|
void AT10GimbalDriver::parserLoop(void)
|
||||||
{
|
{
|
||||||
uint8_t temp;
|
uint8_t temp[65536];
|
||||||
|
uint32_t i = 0, getCount = 0;
|
||||||
|
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
if (IO->inPutByte(&temp))
|
getCount = IO->inPutBytes(temp);
|
||||||
|
|
||||||
|
for (i = 0; i < getCount; i++)
|
||||||
{
|
{
|
||||||
parser(temp);
|
parser(temp[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -387,7 +361,7 @@ void AT10GimbalDriver::getStdRxPack(void)
|
|||||||
{
|
{
|
||||||
if (stdRxQueue->outCell(tempBuffer))
|
if (stdRxQueue->outCell(tempBuffer))
|
||||||
{
|
{
|
||||||
msgCustomCallback(tempBuffer);
|
msgCustomCallback(tempBuffer, msgCaller);
|
||||||
convert(tempBuffer);
|
convert(tempBuffer);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -400,20 +374,25 @@ void AT10GimbalDriver::getExtRxPack(void)
|
|||||||
{
|
{
|
||||||
if (rxQueue->outCell(tempBuffer))
|
if (rxQueue->outCell(tempBuffer))
|
||||||
{
|
{
|
||||||
msgCustomCallback(tempBuffer);
|
msgCustomCallback(tempBuffer, msgCaller);
|
||||||
convert(tempBuffer);
|
convert(tempBuffer);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AT10GimbalDriver::parserStart(amovGimbal::pStateInvoke callback)
|
void AT10GimbalDriver::parserStart(pAmovGimbalStateInvoke callback, void *caller)
|
||||||
{
|
{
|
||||||
this->updateGimbalStateCallback = callback;
|
this->updateGimbalStateCallback = callback;
|
||||||
|
this->updataCaller = caller;
|
||||||
|
|
||||||
std::thread parser(&AT10GimbalDriver::parserLoop, this);
|
std::thread parser(&AT10GimbalDriver::parserLoop, this);
|
||||||
std::thread getStdRxPackLoop(&AT10GimbalDriver::getStdRxPack, this);
|
std::thread getStdRxPackLoop(&AT10GimbalDriver::getStdRxPack, this);
|
||||||
std::thread getExtRxPackLooP(&AT10GimbalDriver::getExtRxPack, this);
|
std::thread getExtRxPackLooP(&AT10GimbalDriver::getExtRxPack, this);
|
||||||
|
|
||||||
|
this->parserThreadHanle = parser.native_handle();
|
||||||
|
this->stackThreadHanle = getStdRxPackLoop.native_handle();
|
||||||
|
this->extStackThreadHandle = getExtRxPackLooP.native_handle();
|
||||||
|
|
||||||
parser.detach();
|
parser.detach();
|
||||||
getStdRxPackLoop.detach();
|
getStdRxPackLoop.detach();
|
||||||
getExtRxPackLooP.detach();
|
getExtRxPackLooP.detach();
|
||||||
|
|||||||
@@ -3,19 +3,17 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-28 12:24:21
|
* @Date: 2022-10-28 12:24:21
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-08-25 19:28:55
|
* @LastEditTime: 2023-12-06 10:27:48
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_driver.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h
|
||||||
*/
|
*/
|
||||||
#include "../amov_gimbal.h"
|
#ifndef __AT10_DRIVER_H
|
||||||
|
#define __AT10_DRIVER_H
|
||||||
#include "../amov_gimbal_private.h"
|
#include "../amov_gimbal_private.h"
|
||||||
#include "AT10_gimbal_struct.h"
|
#include "AT10_gimbal_struct.h"
|
||||||
#include <mutex>
|
#include <mutex>
|
||||||
#include <malloc.h>
|
#include <malloc.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#ifndef __AT10_DRIVER_H
|
|
||||||
#define __AT10_DRIVER_H
|
|
||||||
|
|
||||||
class AT10GimbalDriver : protected amovGimbal::amovGimbalBase
|
class AT10GimbalDriver : protected amovGimbal::amovGimbalBase
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
@@ -32,12 +30,13 @@ private:
|
|||||||
void sendHeart(void);
|
void sendHeart(void);
|
||||||
void sendStd(void);
|
void sendStd(void);
|
||||||
|
|
||||||
void parserStart(amovGimbal::pStateInvoke callback);
|
void parserStart(pAmovGimbalStateInvoke callback, void *caller);
|
||||||
void parserLoop(void);
|
void parserLoop(void);
|
||||||
void getExtRxPack(void);
|
void getExtRxPack(void);
|
||||||
void getStdRxPack(void);
|
void getStdRxPack(void);
|
||||||
|
|
||||||
// bool getRxPack(OUT void *pack);
|
std::thread::native_handle_type sendHreatThreadHandle;
|
||||||
|
std::thread::native_handle_type extStackThreadHandle;
|
||||||
|
|
||||||
bool parser(IN uint8_t byte);
|
bool parser(IN uint8_t byte);
|
||||||
void convert(void *buf);
|
void convert(void *buf);
|
||||||
@@ -46,18 +45,18 @@ private:
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// funtions
|
// funtions
|
||||||
uint32_t setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos);
|
uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
uint32_t setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed);
|
uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
uint32_t setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed);
|
uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
||||||
uint32_t setGimabalHome(void);
|
uint32_t setGimabalHome(void);
|
||||||
|
|
||||||
uint32_t setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
uint32_t setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
|
||||||
uint32_t takePic(void);
|
uint32_t takePic(void);
|
||||||
uint32_t setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState);
|
uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
|
||||||
uint32_t extensionFuntions(void* cmd);
|
uint32_t extensionFuntions(void *cmd);
|
||||||
|
|
||||||
// builds
|
// builds
|
||||||
static amovGimbal::amovGimbalBase *creat(amovGimbal::IOStreamBase *_IO)
|
static amovGimbal::amovGimbalBase *creat(amovGimbal::IOStreamBase *_IO)
|
||||||
@@ -76,6 +75,13 @@ public:
|
|||||||
{
|
{
|
||||||
delete stdTxQueue;
|
delete stdTxQueue;
|
||||||
}
|
}
|
||||||
|
// set thread kill anytime
|
||||||
|
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
|
||||||
|
parserThreadHanle = parserThreadHanle == 0 ? 0 : pthread_cancel(parserThreadHanle);
|
||||||
|
sendThreadHanle = sendThreadHanle == 0 ? 0 : pthread_cancel(sendThreadHanle);
|
||||||
|
stackThreadHanle = stackThreadHanle == 0 ? 0 : pthread_cancel(stackThreadHanle);
|
||||||
|
sendHreatThreadHandle = sendHreatThreadHandle == 0 ? 0 : pthread_cancel(sendHreatThreadHandle);
|
||||||
|
extStackThreadHandle = extStackThreadHandle == 0 ? 0 : pthread_cancel(extStackThreadHandle);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -3,7 +3,7 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-03-02 10:00:52
|
* @Date: 2023-03-02 10:00:52
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-09-07 10:56:15
|
* @LastEditTime: 2023-11-27 16:27:18
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_funtion.cpp
|
* @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_funtion.cpp
|
||||||
*/
|
*/
|
||||||
#include "AT10_gimbal_driver.h"
|
#include "AT10_gimbal_driver.h"
|
||||||
@@ -17,7 +17,7 @@
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t AT10GimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos)
|
uint32_t AT10GimbalDriver::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
{
|
{
|
||||||
int16_t yaw, pitch;
|
int16_t yaw, pitch;
|
||||||
AT10::GIMBAL_CMD_A1_MSG_T temp;
|
AT10::GIMBAL_CMD_A1_MSG_T temp;
|
||||||
@@ -35,14 +35,14 @@ uint32_t AT10GimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &po
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* It takes a struct of type amovGimbal::AMOV_GIMBAL_POS_T and converts it to a struct of type
|
* It takes a struct of type AMOV_GIMBAL_POS_T and converts it to a struct of type
|
||||||
* G1::GIMBAL_SET_POS_MSG_T
|
* G1::GIMBAL_SET_POS_MSG_T
|
||||||
*
|
*
|
||||||
* @param speed the speed of the gimbal
|
* @param speed the speed of the gimbal
|
||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t AT10GimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed)
|
uint32_t AT10GimbalDriver::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
{
|
{
|
||||||
int16_t speedYaw, speedPitch;
|
int16_t speedYaw, speedPitch;
|
||||||
AT10::GIMBAL_CMD_A1_MSG_T temp;
|
AT10::GIMBAL_CMD_A1_MSG_T temp;
|
||||||
@@ -66,7 +66,7 @@ uint32_t AT10GimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t AT10GimbalDriver::setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed)
|
uint32_t AT10GimbalDriver::setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed)
|
||||||
{
|
{
|
||||||
state.maxFollow.pitch = fabs(followSpeed.pitch * 100);
|
state.maxFollow.pitch = fabs(followSpeed.pitch * 100);
|
||||||
state.maxFollow.yaw = fabs(followSpeed.yaw * 100);
|
state.maxFollow.yaw = fabs(followSpeed.yaw * 100);
|
||||||
@@ -110,10 +110,10 @@ uint32_t AT10GimbalDriver::takePic(void)
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the serial port.
|
* @return The return value is the number of bytes written to the serial port.
|
||||||
*/
|
*/
|
||||||
uint32_t AT10GimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState)
|
uint32_t AT10GimbalDriver::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
{
|
{
|
||||||
uint16_t temp;
|
uint16_t temp;
|
||||||
if (newState == amovGimbal::AMOV_GIMBAL_VIDEO_T::AMOV_GIMBAL_VIDEO_TAKE)
|
if (newState == AMOV_GIMBAL_VIDEO_T::AMOV_GIMBAL_VIDEO_TAKE)
|
||||||
{
|
{
|
||||||
temp = 0x14 << 3;
|
temp = 0x14 << 3;
|
||||||
}
|
}
|
||||||
@@ -127,20 +127,20 @@ uint32_t AT10GimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newSta
|
|||||||
return pack(AT10::GIMBAL_CMD_STD_CAMERA, (uint8_t *)&data, sizeof(uint16_t));
|
return pack(AT10::GIMBAL_CMD_STD_CAMERA, (uint8_t *)&data, sizeof(uint16_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t AT10GimbalDriver::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
uint32_t AT10GimbalDriver::setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
{
|
{
|
||||||
if (targetRate == 0.0f)
|
if (targetRate == 0.0f)
|
||||||
{
|
{
|
||||||
uint16_t temp = 0;
|
uint16_t temp = 0;
|
||||||
switch (zoom)
|
switch (zoom)
|
||||||
{
|
{
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_IN:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_IN:
|
||||||
temp = 0X08 << 3;
|
temp = 0X08 << 3;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_OUT:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_OUT:
|
||||||
temp = 0X09 << 3;
|
temp = 0X09 << 3;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_STOP:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_STOP:
|
||||||
temp = 0X01 << 3;
|
temp = 0X01 << 3;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@@ -160,18 +160,18 @@ uint32_t AT10GimbalDriver::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, fl
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t AT10GimbalDriver::setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
uint32_t AT10GimbalDriver::setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
{
|
{
|
||||||
uint16_t temp = 0;
|
uint16_t temp = 0;
|
||||||
switch (zoom)
|
switch (zoom)
|
||||||
{
|
{
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_IN:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_IN:
|
||||||
temp = 0X0B << 3;
|
temp = 0X0B << 3;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_OUT:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_OUT:
|
||||||
temp = 0X0A << 3;
|
temp = 0X0A << 3;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_STOP:
|
case AMOV_GIMBAL_ZOOM_T::AMOV_GIMBAL_ZOOM_STOP:
|
||||||
temp = 0X01 << 3;
|
temp = 0X01 << 3;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|||||||
@@ -1,36 +0,0 @@
|
|||||||
add_library(AMOV_Gimbal ${LIB_FLAG})
|
|
||||||
|
|
||||||
SET(CMAKE_CXX_FLAGS_DEBUG "$ENV{CXXFLAGS} -O0 -Wall -g2 -ggdb -fPIC")
|
|
||||||
SET(CMAKE_CXX_FLAGS_RELEASE "$ENV{CXXFLAGS} -O3 -Wall -fPIC")
|
|
||||||
|
|
||||||
add_definitions(
|
|
||||||
-DMAX_QUEUE_SIZE=100
|
|
||||||
)
|
|
||||||
|
|
||||||
add_subdirectory(FIFO)
|
|
||||||
########## add types of gimbal ##############
|
|
||||||
add_subdirectory(G1)
|
|
||||||
add_subdirectory(G2)
|
|
||||||
add_subdirectory(Q10f)
|
|
||||||
add_subdirectory(AT10)
|
|
||||||
|
|
||||||
file(GLOB LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp)
|
|
||||||
|
|
||||||
target_sources(AMOV_Gimbal
|
|
||||||
PRIVATE
|
|
||||||
${LIB_FILES}
|
|
||||||
)
|
|
||||||
|
|
||||||
target_link_libraries(AMOV_Gimbal
|
|
||||||
PRIVATE
|
|
||||||
Gimabl_G1
|
|
||||||
Gimabl_G2
|
|
||||||
Gimabl_Q10f
|
|
||||||
Gimabl_AT10
|
|
||||||
)
|
|
||||||
|
|
||||||
target_include_directories(AMOV_Gimbal
|
|
||||||
PUBLIC
|
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}
|
|
||||||
)
|
|
||||||
|
|
||||||
@@ -1,13 +0,0 @@
|
|||||||
add_library(FIFO)
|
|
||||||
|
|
||||||
file(GLOB LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp)
|
|
||||||
|
|
||||||
target_sources(FIFO
|
|
||||||
PRIVATE
|
|
||||||
${LIB_FILES}
|
|
||||||
)
|
|
||||||
|
|
||||||
target_include_directories(FIFO
|
|
||||||
PUBLIC
|
|
||||||
${CMAKE_CURRENT_SOURCE_DIR}
|
|
||||||
)
|
|
||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author : Aiyangsky
|
* @Author : Aiyangsky
|
||||||
* @Date : 2022-08-26 21:42:10
|
* @Date : 2022-08-26 21:42:10
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-07-21 16:10:16
|
* @LastEditTime: 2023-11-28 11:47:34
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/FIFO/Ring_Fifo.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author : Aiyangsky
|
* @Author : Aiyangsky
|
||||||
* @Date : 2022-08-26 21:42:02
|
* @Date : 2022-08-26 21:42:02
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-08-16 21:22:46
|
* @LastEditTime: 2023-11-28 11:47:39
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/FIFO/Ring_Fifo.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef RING_FIFO_H
|
#ifndef RING_FIFO_H
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2022-10-28 14:10:02
|
* @LastEditTime: 2023-12-05 16:30:13
|
||||||
* @FilePath: \amov-gimbal-sdk\src\G1\g1_gimbal_crc32.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h
|
||||||
*/
|
*/
|
||||||
#ifndef G1_GIMBAL_CRC32_H
|
#ifndef G1_GIMBAL_CRC32_H
|
||||||
#define G1_GIMBAL_CRC32_H
|
#define G1_GIMBAL_CRC32_H
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-09-07 11:01:25
|
* @LastEditTime: 2023-12-05 17:22:57
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_driver.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp
|
||||||
*/
|
*/
|
||||||
#include "g1_gimbal_driver.h"
|
#include "g1_gimbal_driver.h"
|
||||||
#include "g1_gimbal_crc32.h"
|
#include "g1_gimbal_crc32.h"
|
||||||
@@ -75,7 +75,7 @@ void g1GimbalDriver::convert(void *buf)
|
|||||||
state.rel.pitch = tempPos->HALL_pitch * G1_SCALE_FACTOR;
|
state.rel.pitch = tempPos->HALL_pitch * G1_SCALE_FACTOR;
|
||||||
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
||||||
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
||||||
state.fov.x, state.fov.y);
|
state.fov.x, state.fov.y, updataCaller);
|
||||||
mState.unlock();
|
mState.unlock();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|||||||
@@ -3,19 +3,18 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-28 12:24:21
|
* @Date: 2022-10-28 12:24:21
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-09-07 02:31:19
|
* @LastEditTime: 2023-12-05 16:29:58
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_driver.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h
|
||||||
*/
|
*/
|
||||||
#include "../amov_gimbal.h"
|
#ifndef __G1_DRIVER_H
|
||||||
|
#define __G1_DRIVER_H
|
||||||
|
|
||||||
#include "../amov_gimbal_private.h"
|
#include "../amov_gimbal_private.h"
|
||||||
#include "g1_gimbal_struct.h"
|
#include "g1_gimbal_struct.h"
|
||||||
#include <mutex>
|
#include <mutex>
|
||||||
#include <malloc.h>
|
#include <malloc.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#ifndef __G1_DRIVER_H
|
|
||||||
#define __G1_DRIVER_H
|
|
||||||
|
|
||||||
class g1GimbalDriver : protected amovGimbal::amovGimbalBase
|
class g1GimbalDriver : protected amovGimbal::amovGimbalBase
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
@@ -29,22 +28,22 @@ private:
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// funtions
|
// funtions
|
||||||
uint32_t setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos);
|
uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
uint32_t setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed);
|
uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
uint32_t setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed);
|
uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
||||||
uint32_t setGimabalHome(void);
|
uint32_t setGimabalHome(void);
|
||||||
|
|
||||||
uint32_t takePic(void);
|
uint32_t takePic(void);
|
||||||
uint32_t setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState);
|
uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
|
||||||
uint32_t attitudeCorrection(const amovGimbal::AMOV_GIMBAL_QUATERNION_T &quaterion,
|
uint32_t attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &speed,
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &acc,
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
void *extenData);
|
void *extenData);
|
||||||
|
|
||||||
uint32_t attitudeCorrection(const amovGimbal::AMOV_GIMBAL_POS_T &pos,
|
uint32_t attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &seppd,
|
const AMOV_GIMBAL_VELOCITY_T &seppd,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &acc,
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
void *extenData);
|
void *extenData);
|
||||||
uint32_t extensionFuntions(void *cmd);
|
uint32_t extensionFuntions(void *cmd);
|
||||||
|
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-03-02 10:00:52
|
* @Date: 2023-03-02 10:00:52
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-09-07 10:50:30
|
* @LastEditTime: 2023-12-05 16:29:51
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_funtion.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp
|
||||||
*/
|
*/
|
||||||
#include "g1_gimbal_driver.h"
|
#include "g1_gimbal_driver.h"
|
||||||
#include "g1_gimbal_crc32.h"
|
#include "g1_gimbal_crc32.h"
|
||||||
@@ -18,7 +18,7 @@
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos)
|
uint32_t g1GimbalDriver::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
{
|
{
|
||||||
G1::GIMBAL_SET_POS_MSG_T temp;
|
G1::GIMBAL_SET_POS_MSG_T temp;
|
||||||
temp.mode = G1::GIMBAL_CMD_POS_MODE_ANGLE;
|
temp.mode = G1::GIMBAL_CMD_POS_MODE_ANGLE;
|
||||||
@@ -32,14 +32,14 @@ uint32_t g1GimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* It takes a struct of type amovGimbal::AMOV_GIMBAL_POS_T and converts it to a struct of type
|
* It takes a struct of type AMOV_GIMBAL_POS_T and converts it to a struct of type
|
||||||
* G1::GIMBAL_SET_POS_MSG_T
|
* G1::GIMBAL_SET_POS_MSG_T
|
||||||
*
|
*
|
||||||
* @param speed the speed of the gimbal
|
* @param speed the speed of the gimbal
|
||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed)
|
uint32_t g1GimbalDriver::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
{
|
{
|
||||||
G1::GIMBAL_SET_POS_MSG_T temp;
|
G1::GIMBAL_SET_POS_MSG_T temp;
|
||||||
temp.mode = G1::GIMBAL_CMD_POS_MODE_SPEED;
|
temp.mode = G1::GIMBAL_CMD_POS_MODE_SPEED;
|
||||||
@@ -59,7 +59,7 @@ uint32_t g1GimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &sp
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed)
|
uint32_t g1GimbalDriver::setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed)
|
||||||
{
|
{
|
||||||
state.maxFollow.pitch = followSpeed.pitch / G1_SCALE_FACTOR;
|
state.maxFollow.pitch = followSpeed.pitch / G1_SCALE_FACTOR;
|
||||||
state.maxFollow.roll = followSpeed.roll / G1_SCALE_FACTOR;
|
state.maxFollow.roll = followSpeed.roll / G1_SCALE_FACTOR;
|
||||||
@@ -100,18 +100,18 @@ uint32_t g1GimbalDriver::takePic(void)
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the serial port.
|
* @return The return value is the number of bytes written to the serial port.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState)
|
uint32_t g1GimbalDriver::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
{
|
{
|
||||||
uint8_t temp = G1::GIMBAL_CMD_CAMERA_REC;
|
uint8_t temp = G1::GIMBAL_CMD_CAMERA_REC;
|
||||||
|
|
||||||
mState.lock();
|
mState.lock();
|
||||||
if (state.video == amovGimbal::AMOV_GIMBAL_VIDEO_TAKE)
|
if (state.video == AMOV_GIMBAL_VIDEO_TAKE)
|
||||||
{
|
{
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_OFF;
|
state.video = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_TAKE;
|
state.video = AMOV_GIMBAL_VIDEO_TAKE;
|
||||||
}
|
}
|
||||||
mState.unlock();
|
mState.unlock();
|
||||||
|
|
||||||
@@ -124,10 +124,10 @@ uint32_t g1GimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState
|
|||||||
*
|
*
|
||||||
* @param quaterion The "quaterion" parameter is a structure of type "AMOV_GIMBAL_QUATERNION_T" which
|
* @param quaterion The "quaterion" parameter is a structure of type "AMOV_GIMBAL_QUATERNION_T" which
|
||||||
* contains the following fields:
|
* contains the following fields:
|
||||||
* @param speed The "speed" parameter is of type `amovGimbal::AMOV_GIMBAL_VELOCITY_T` and represents
|
* @param speed The "speed" parameter is of type `AMOV_GIMBAL_VELOCITY_T` and represents
|
||||||
* the velocity of the gimbal. It contains three components: `x`, `y`, and `z`, which represent the
|
* the velocity of the gimbal. It contains three components: `x`, `y`, and `z`, which represent the
|
||||||
* velocity in the respective axes.
|
* velocity in the respective axes.
|
||||||
* @param acc The "acc" parameter is of type "amovGimbal::AMOV_GIMBAL_VELOCITY_T" and represents the
|
* @param acc The "acc" parameter is of type "AMOV_GIMBAL_VELOCITY_T" and represents the
|
||||||
* acceleration of the gimbal in three dimensions (x, y, z).
|
* acceleration of the gimbal in three dimensions (x, y, z).
|
||||||
* @param extenData The extenData parameter is a void pointer that can be used to pass additional data
|
* @param extenData The extenData parameter is a void pointer that can be used to pass additional data
|
||||||
* to the attitudeCorrection function. In this case, it is being cast to a float pointer and then
|
* to the attitudeCorrection function. In this case, it is being cast to a float pointer and then
|
||||||
@@ -136,9 +136,9 @@ uint32_t g1GimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState
|
|||||||
*
|
*
|
||||||
* @return a uint32_t value.
|
* @return a uint32_t value.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::attitudeCorrection(const amovGimbal::AMOV_GIMBAL_QUATERNION_T &quaterion,
|
uint32_t g1GimbalDriver::attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &speed,
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &acc,
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
void *extenData)
|
void *extenData)
|
||||||
{
|
{
|
||||||
G1::GIMBAL_ATT_CORR_MSG_T temp;
|
G1::GIMBAL_ATT_CORR_MSG_T temp;
|
||||||
@@ -161,12 +161,12 @@ uint32_t g1GimbalDriver::attitudeCorrection(const amovGimbal::AMOV_GIMBAL_QUATER
|
|||||||
* The function `attitudeCorrection` calculates the attitude correction for a gimbal based on the given
|
* The function `attitudeCorrection` calculates the attitude correction for a gimbal based on the given
|
||||||
* position, velocity, and acceleration values.
|
* position, velocity, and acceleration values.
|
||||||
*
|
*
|
||||||
* @param pos The "pos" parameter is of type amovGimbal::AMOV_GIMBAL_POS_T and represents the current
|
* @param pos The "pos" parameter is of type AMOV_GIMBAL_POS_T and represents the current
|
||||||
* position of the gimbal. It contains the pitch, roll, and yaw angles of the gimbal.
|
* position of the gimbal. It contains the pitch, roll, and yaw angles of the gimbal.
|
||||||
* @param seppd seppd stands for "Separate Pointing Device" and it represents the velocity of the
|
* @param seppd seppd stands for "Separate Pointing Device" and it represents the velocity of the
|
||||||
* gimbal in terms of pitch, roll, and yaw. It is of type `amovGimbal::AMOV_GIMBAL_VELOCITY_T` which
|
* gimbal in terms of pitch, roll, and yaw. It is of type `AMOV_GIMBAL_VELOCITY_T` which
|
||||||
* likely contains three float values for pitch,
|
* likely contains three float values for pitch,
|
||||||
* @param acc The "acc" parameter is of type "amovGimbal::AMOV_GIMBAL_VELOCITY_T" and represents the
|
* @param acc The "acc" parameter is of type "AMOV_GIMBAL_VELOCITY_T" and represents the
|
||||||
* acceleration of the gimbal in three dimensions (x, y, z).
|
* acceleration of the gimbal in three dimensions (x, y, z).
|
||||||
* @param extenData The `extenData` parameter is a void pointer that can be used to pass additional
|
* @param extenData The `extenData` parameter is a void pointer that can be used to pass additional
|
||||||
* data to the `attitudeCorrection` function. In this code snippet, it is assumed that `extenData` is a
|
* data to the `attitudeCorrection` function. In this code snippet, it is assumed that `extenData` is a
|
||||||
@@ -174,9 +174,9 @@ uint32_t g1GimbalDriver::attitudeCorrection(const amovGimbal::AMOV_GIMBAL_QUATER
|
|||||||
*
|
*
|
||||||
* @return a uint32_t value.
|
* @return a uint32_t value.
|
||||||
*/
|
*/
|
||||||
uint32_t g1GimbalDriver::attitudeCorrection(const amovGimbal::AMOV_GIMBAL_POS_T &pos,
|
uint32_t g1GimbalDriver::attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &seppd,
|
const AMOV_GIMBAL_VELOCITY_T &seppd,
|
||||||
const amovGimbal::AMOV_GIMBAL_VELOCITY_T &acc,
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
void *extenData)
|
void *extenData)
|
||||||
{
|
{
|
||||||
G1::GIMBAL_ATT_CORR_MSG_T temp;
|
G1::GIMBAL_ATT_CORR_MSG_T temp;
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:07
|
* @Date: 2022-10-27 18:10:07
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-09-07 10:45:13
|
* @LastEditTime: 2023-12-05 16:29:48
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_struct.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h
|
||||||
*/
|
*/
|
||||||
#ifndef G1_GIMBAL_STRUCT_H
|
#ifndef G1_GIMBAL_STRUCT_H
|
||||||
#define G1_GIMBAL_STRUCT_H
|
#define G1_GIMBAL_STRUCT_H
|
||||||
|
|||||||
41
gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h
Normal file
41
gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h
Normal file
@@ -0,0 +1,41 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-10-20 16:33:07
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 16:29:39
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h
|
||||||
|
*/
|
||||||
|
#ifndef GX40_GIMBAL_CRC16_H
|
||||||
|
#define GX40_GIMBAL_CRC16_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace GX40
|
||||||
|
{
|
||||||
|
const static uint16_t crc16Tab[16] = {
|
||||||
|
0x0000, 0x1021, 0x2042, 0x3063,
|
||||||
|
0x4084, 0x50a5, 0x60c6, 0x70e7,
|
||||||
|
0x8108, 0x9129, 0xa14a, 0xb16b,
|
||||||
|
0xc18c, 0xd1ad, 0xe1ce, 0xf1ef};
|
||||||
|
|
||||||
|
static inline uint16_t CalculateCrc16(const uint8_t *ptr, uint8_t len)
|
||||||
|
{
|
||||||
|
uint16_t crc = 0;
|
||||||
|
uint8_t temp;
|
||||||
|
|
||||||
|
while (len-- != 0)
|
||||||
|
{
|
||||||
|
temp = crc >> 12;
|
||||||
|
crc <<= 4;
|
||||||
|
crc ^= crc16Tab[temp ^ (*ptr >> 4)];
|
||||||
|
temp = crc >> 12;
|
||||||
|
crc <<= 4;
|
||||||
|
crc ^= crc16Tab[temp ^ (*ptr & 0x0F)];
|
||||||
|
ptr++;
|
||||||
|
}
|
||||||
|
crc = (crc >> 8) | (crc << 8);
|
||||||
|
return (crc);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
302
gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp
Normal file
302
gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp
Normal file
@@ -0,0 +1,302 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-10-20 16:08:17
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-06 10:27:28
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp
|
||||||
|
*/
|
||||||
|
#include <string.h>
|
||||||
|
#include "GX40_gimbal_driver.h"
|
||||||
|
#include "GX40_gimbal_crc16.h"
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The above function is a constructor for the GX40GimbalDriver class in C++, which initializes member
|
||||||
|
* variables and sets the parser state to idle.
|
||||||
|
*
|
||||||
|
* @param _IO _IO is a pointer to an object of type amovGimbal::IOStreamBase. It is used to communicate
|
||||||
|
* with the gimbal device.
|
||||||
|
*/
|
||||||
|
GX40GimbalDriver::GX40GimbalDriver(amovGimbal::IOStreamBase *_IO) : amovGimbal::amovGimbalBase(_IO)
|
||||||
|
{
|
||||||
|
rxQueue = new fifoRing(sizeof(GX40::GIMBAL_FRAME_T), MAX_QUEUE_SIZE);
|
||||||
|
txQueue = new fifoRing(sizeof(GX40::GIMBAL_FRAME_T), MAX_QUEUE_SIZE);
|
||||||
|
|
||||||
|
targetPos[0] = 0;
|
||||||
|
targetPos[1] = 0;
|
||||||
|
targetPos[2] = 0;
|
||||||
|
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `nopSend` continuously sends a "no operation" command to a GX40 gimbal driver.
|
||||||
|
*/
|
||||||
|
void GX40GimbalDriver::nopSend(void)
|
||||||
|
{
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
// 50Hz
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(20));
|
||||||
|
pack(GX40::GIMBAL_CMD_NOP, nullptr, 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `parserStart` initializes the gimbal driver by setting the callback function, creating
|
||||||
|
* two threads for the main loop and sending NOP commands, and detaching the threads.
|
||||||
|
*
|
||||||
|
* @param callback The parameter "callback" is of type "amovGimbal::pStateInvoke", which is a function
|
||||||
|
* pointer type. It is used to specify a callback function that will be invoked when the gimbal state
|
||||||
|
* is updated.
|
||||||
|
*/
|
||||||
|
void GX40GimbalDriver::parserStart(pAmovGimbalStateInvoke callback, void *caller)
|
||||||
|
{
|
||||||
|
this->updateGimbalStateCallback = callback;
|
||||||
|
this->updataCaller = caller;
|
||||||
|
|
||||||
|
std::thread mainLoop(&GX40GimbalDriver::mainLoop, this);
|
||||||
|
std::thread sendNop(&GX40GimbalDriver::nopSend, this);
|
||||||
|
|
||||||
|
this->stackThreadHanle = mainLoop.native_handle();
|
||||||
|
this->nopSendThreadHandle = sendNop.native_handle();
|
||||||
|
|
||||||
|
mainLoop.detach();
|
||||||
|
sendNop.detach();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `pack` in the `GX40GimbalDriver` class is responsible for packing data into a frame for
|
||||||
|
* transmission.
|
||||||
|
*
|
||||||
|
* @param uint32_t The parameter `cmd` is an unsigned 32-bit integer representing the command.
|
||||||
|
* @param pPayload The `pPayload` parameter is a pointer to the payload data that needs to be packed.
|
||||||
|
* It is of type `uint8_t*`, which means it is a pointer to an array of unsigned 8-bit integers. The
|
||||||
|
* payload data is stored in this array.
|
||||||
|
* @param payloadSize The parameter `payloadSize` represents the size of the payload data in bytes. It
|
||||||
|
* is used to determine the size of the payload data that needs to be packed into the `temp` structure.
|
||||||
|
*
|
||||||
|
* @return a uint32_t value, which is stored in the variable "ret".
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::pack(IN uint32_t cmd, uint8_t *pPayload, uint8_t payloadSize)
|
||||||
|
{
|
||||||
|
uint32_t ret = 0;
|
||||||
|
GX40::GIMBAL_FRAME_T temp;
|
||||||
|
memset(&temp, 0, sizeof(GX40::GIMBAL_FRAME_T));
|
||||||
|
GX40::GIMBAL_PRIMARY_MASTER_FRAME_T *primary = (GX40::GIMBAL_PRIMARY_MASTER_FRAME_T *)temp.primaryData;
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
|
||||||
|
primary->state = 0X00;
|
||||||
|
// 姿态数据&指令数据填充
|
||||||
|
primary->roll = targetPos[0];
|
||||||
|
primary->pitch = targetPos[1];
|
||||||
|
primary->yaw = targetPos[2];
|
||||||
|
|
||||||
|
primary->state |= (0X01 << 2);
|
||||||
|
|
||||||
|
temp.otherData[0] = cmd;
|
||||||
|
memcpy(temp.otherData + 1, pPayload, payloadSize);
|
||||||
|
|
||||||
|
// 固定字节填充
|
||||||
|
temp.head.u16 = XF_SEND_HEAD;
|
||||||
|
temp.version = 0X01;
|
||||||
|
primary->secondaryFlag = 0X01;
|
||||||
|
temp.lenght.u16 = 69 + payloadSize + 1 + 2;
|
||||||
|
|
||||||
|
// 惯导数据填充
|
||||||
|
std::chrono::milliseconds nowTs = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch());
|
||||||
|
// over 1s GNSS has losed
|
||||||
|
if ((nowTs.count() - upDataTs.count()) < std::chrono::milliseconds(1500).count())
|
||||||
|
{
|
||||||
|
primary->selfRoll = (int16_t)(-(carrierPos.roll / 0.01f));
|
||||||
|
primary->selfPitch = (int16_t)(-(carrierPos.pitch / 0.01f));
|
||||||
|
primary->selfYaw = (int16_t)(carrierPos.yaw / 0.01f);
|
||||||
|
primary->accE = (int16_t)(carrierAcc.y / 0.01f);
|
||||||
|
primary->accN = (int16_t)(carrierAcc.x / 0.01f);
|
||||||
|
primary->accUp = (int16_t)(carrierAcc.z / 0.01f);
|
||||||
|
primary->speedE = (int16_t)(carrierSpeed.y / 0.01f);
|
||||||
|
primary->speedN = (int16_t)(carrierSpeed.x / 0.01f);
|
||||||
|
primary->speedUp = (int16_t)(carrierSpeed.z / 0.01f);
|
||||||
|
|
||||||
|
carrierGNSS.GPSweeks = ((nowTs.count() / 1000) - 315964800) / 604800;
|
||||||
|
carrierGNSS.GPSms = nowTs.count() - (carrierGNSS.GPSweeks * 604800000);
|
||||||
|
|
||||||
|
memcpy(temp.secondaryData, &carrierGNSS, sizeof(GX40::GIMBAL_SECONDARY_MASTER_FRAME_T));
|
||||||
|
|
||||||
|
primary->state |= (0X01 << 0);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
primary->state &= (~(0X01 << 0));
|
||||||
|
}
|
||||||
|
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
|
||||||
|
// 校验
|
||||||
|
*(uint16_t *)(&temp.otherData[payloadSize + 1]) = GX40::CalculateCrc16((uint8_t *)&temp, 69 + 1 + payloadSize);
|
||||||
|
|
||||||
|
// 添加至发送队列
|
||||||
|
if (txQueue->inCell(&temp))
|
||||||
|
{
|
||||||
|
ret = temp.lenght.u16;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `convert` takes a buffer and extracts data from it to update the state of a gimbal
|
||||||
|
* driver.
|
||||||
|
*
|
||||||
|
* @param buf The `buf` parameter is a void pointer that points to a buffer containing data that needs
|
||||||
|
* to be converted.
|
||||||
|
*/
|
||||||
|
void GX40GimbalDriver::convert(void *buf)
|
||||||
|
{
|
||||||
|
GX40::GIMBAL_FRAME_T *temp;
|
||||||
|
GX40::GIMBAL_PRIMARY_SLAVE_FRAME_T *primary;
|
||||||
|
GX40::GIMBAL_SECONDARY_SLAVE_FRAME_T *secondary;
|
||||||
|
temp = reinterpret_cast<GX40::GIMBAL_FRAME_T *>(buf);
|
||||||
|
primary = (GX40::GIMBAL_PRIMARY_SLAVE_FRAME_T *)temp->primaryData;
|
||||||
|
secondary = (GX40::GIMBAL_SECONDARY_SLAVE_FRAME_T *)temp->secondaryData;
|
||||||
|
|
||||||
|
mState.lock();
|
||||||
|
this->state.workMode = (AMOV_GIMBAL_SERVO_MODE_T)primary->workMode;
|
||||||
|
this->state.cameraFlag = (AMOV_GIMBAL_CAMERA_FLAG_T)primary->state;
|
||||||
|
// 应该需要再解算一下,才能出具体的框架角度
|
||||||
|
this->state.rel.yaw = -(primary->motorYaw * XF_ANGLE_DPI);
|
||||||
|
this->state.rel.yaw = this->state.rel.yaw < -180.0f ? this->state.rel.yaw + 360.0f : this->state.rel.yaw;
|
||||||
|
this->state.rel.pitch = -(primary->motorPitch * XF_ANGLE_DPI);
|
||||||
|
this->state.rel.roll = -(primary->motorRoll * XF_ANGLE_DPI);
|
||||||
|
|
||||||
|
this->state.abs.yaw = -(primary->yaw * XF_ANGLE_DPI);
|
||||||
|
this->state.abs.yaw = this->state.abs.yaw < -180.0f ? this->state.abs.yaw + 360.0f : this->state.abs.yaw;
|
||||||
|
|
||||||
|
this->state.abs.pitch = -(primary->pitch * XF_ANGLE_DPI);
|
||||||
|
this->state.abs.roll = -(primary->roll * XF_ANGLE_DPI);
|
||||||
|
|
||||||
|
this->state.relSpeed.yaw = -(primary->speedYaw * XF_ANGLE_DPI);
|
||||||
|
this->state.relSpeed.pitch = -(primary->speedPitch * XF_ANGLE_DPI);
|
||||||
|
this->state.relSpeed.roll = -(primary->speedRoll * XF_ANGLE_DPI);
|
||||||
|
|
||||||
|
// 近似值 不准
|
||||||
|
this->state.fov.x = secondary->camera1Zoom * 0.1f;
|
||||||
|
this->state.fov.x = 60.2f / this->state.fov.x;
|
||||||
|
this->state.fov.y = secondary->camera1Zoom * 0.1f;
|
||||||
|
this->state.fov.y = 36.1f / this->state.fov.y;
|
||||||
|
|
||||||
|
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
||||||
|
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
||||||
|
state.fov.x, state.fov.y, updataCaller);
|
||||||
|
|
||||||
|
mState.unlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function calculates the total length of a data packet by adding the length of the payload to the
|
||||||
|
* size of a uint16_t.
|
||||||
|
*
|
||||||
|
* @param pack The parameter "pack" is a void pointer, which means it can point to any type of data. In
|
||||||
|
* this case, it is expected to point to a structure of type "GX40::GIMBAL_FRAME_T".
|
||||||
|
*
|
||||||
|
* @return the sum of the length of the gimbal frame and the size of a uint16_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::calPackLen(void *pack)
|
||||||
|
{
|
||||||
|
return ((GX40::GIMBAL_FRAME_T *)pack)->lenght.u16;
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* The function `parser` is used to parse incoming data frames in a specific format and returns a
|
||||||
|
* boolean value indicating whether the parsing was successful or not.
|
||||||
|
*
|
||||||
|
* @param uint8_t The parameter `byte` is of type `uint8_t`, which is an unsigned 8-bit integer. It is
|
||||||
|
* used to store a single byte of data that is being parsed by the `GX40GimbalDriver::parser` function.
|
||||||
|
*
|
||||||
|
* @return a boolean value, either true or false.
|
||||||
|
*/
|
||||||
|
bool GX40GimbalDriver::parser(IN uint8_t byte)
|
||||||
|
{
|
||||||
|
bool state = false;
|
||||||
|
static uint8_t payloadLenght = 0;
|
||||||
|
static uint8_t *pRx = nullptr;
|
||||||
|
|
||||||
|
switch (parserState)
|
||||||
|
{
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_IDLE:
|
||||||
|
if (byte == ((XF_RCV_HEAD >> 8) & 0XFF))
|
||||||
|
{
|
||||||
|
rx.head.u8[0] = byte;
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_HEAD;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_HEAD:
|
||||||
|
if (byte == ((XF_RCV_HEAD >> 0) & 0XFF))
|
||||||
|
{
|
||||||
|
rx.head.u8[1] = byte;
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_LEN1;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
|
||||||
|
rx.head.u16 = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_LEN1:
|
||||||
|
rx.lenght.u8[0] = byte;
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_LEN2;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_LEN2:
|
||||||
|
rx.lenght.u8[1] = byte;
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_VERSION;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_VERSION:
|
||||||
|
if (byte == XF_VERSION)
|
||||||
|
{
|
||||||
|
rx.version = byte;
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_PAYLOAD;
|
||||||
|
pRx = rx.primaryData;
|
||||||
|
payloadLenght = rx.lenght.u16 - 5;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
|
||||||
|
rx.head.u16 = 0;
|
||||||
|
rx.lenght.u16 = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GX40::GIMBAL_FRAME_PARSER_STATE_PAYLOAD:
|
||||||
|
*pRx = byte;
|
||||||
|
payloadLenght--;
|
||||||
|
pRx++;
|
||||||
|
if (payloadLenght <= 0)
|
||||||
|
{
|
||||||
|
if (*(uint16_t *)(pRx - sizeof(uint16_t)) == GX40::CalculateCrc16((uint8_t *)&rx, rx.lenght.u16 - 2))
|
||||||
|
{
|
||||||
|
state = true;
|
||||||
|
rxQueue->inCell(&rx);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
memset(&rx, 0, sizeof(GX40::GIMBAL_FRAME_T));
|
||||||
|
}
|
||||||
|
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
|
||||||
|
pRx = nullptr;
|
||||||
|
payloadLenght = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
|
||||||
|
pRx = nullptr;
|
||||||
|
payloadLenght = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return state;
|
||||||
|
}
|
||||||
86
gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h
Normal file
86
gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h
Normal file
@@ -0,0 +1,86 @@
|
|||||||
|
|
||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-10-20 16:08:13
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-06 10:27:05
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h
|
||||||
|
*/
|
||||||
|
#ifndef __GX40_DRIVER_H
|
||||||
|
#define __GX40_DRIVER_H
|
||||||
|
#include "../amov_gimbal_private.h"
|
||||||
|
#include "GX40_gimbal_struct.h"
|
||||||
|
#include <mutex>
|
||||||
|
#include <malloc.h>
|
||||||
|
#include <iostream>
|
||||||
|
#include <chrono>
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
|
class GX40GimbalDriver : public amovGimbal::amovGimbalBase
|
||||||
|
{
|
||||||
|
GX40::GIMBAL_FRAME_PARSER_STATE_T parserState;
|
||||||
|
GX40::GIMBAL_FRAME_T rx;
|
||||||
|
|
||||||
|
std::chrono::milliseconds upDataTs;
|
||||||
|
std::mutex carrierStateMutex;
|
||||||
|
|
||||||
|
int16_t targetPos[3];
|
||||||
|
|
||||||
|
AMOV_GIMBAL_POS_T carrierPos;
|
||||||
|
AMOV_GIMBAL_VELOCITY_T carrierSpeed;
|
||||||
|
AMOV_GIMBAL_VELOCITY_T carrierAcc;
|
||||||
|
GX40::GIMBAL_SECONDARY_MASTER_FRAME_T carrierGNSS;
|
||||||
|
|
||||||
|
std::thread::native_handle_type nopSendThreadHandle;
|
||||||
|
void nopSend(void);
|
||||||
|
void parserStart(pAmovGimbalStateInvoke callback, void *caller);
|
||||||
|
|
||||||
|
public:
|
||||||
|
uint32_t pack(IN uint32_t cmd, uint8_t *pPayload, uint8_t payloadSize);
|
||||||
|
bool parser(IN uint8_t byte);
|
||||||
|
void convert(void *buf);
|
||||||
|
uint32_t calPackLen(void *pack);
|
||||||
|
|
||||||
|
// funtions
|
||||||
|
uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
|
uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
|
uint32_t setGimabalHome(void);
|
||||||
|
|
||||||
|
uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
|
||||||
|
uint32_t takePic(void);
|
||||||
|
uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
uint32_t attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &seppd,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
|
void *extenData);
|
||||||
|
|
||||||
|
uint32_t setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt);
|
||||||
|
uint32_t extensionFuntions(void *cmd);
|
||||||
|
static amovGimbal::amovGimbalBase *creat(amovGimbal::IOStreamBase *_IO)
|
||||||
|
{
|
||||||
|
return new GX40GimbalDriver(_IO);
|
||||||
|
}
|
||||||
|
GX40GimbalDriver(amovGimbal::IOStreamBase *_IO);
|
||||||
|
~GX40GimbalDriver()
|
||||||
|
{
|
||||||
|
if (txQueue != nullptr)
|
||||||
|
{
|
||||||
|
delete txQueue;
|
||||||
|
}
|
||||||
|
if (rxQueue != nullptr)
|
||||||
|
{
|
||||||
|
delete rxQueue;
|
||||||
|
}
|
||||||
|
|
||||||
|
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
|
||||||
|
parserThreadHanle = parserThreadHanle == 0 ? 0 : pthread_cancel(parserThreadHanle);
|
||||||
|
sendThreadHanle = sendThreadHanle == 0 ? 0 : pthread_cancel(sendThreadHanle);
|
||||||
|
stackThreadHanle = stackThreadHanle == 0 ? 0 : pthread_cancel(stackThreadHanle);
|
||||||
|
nopSendThreadHandle = nopSendThreadHandle == 0 ? 0 : pthread_cancel(nopSendThreadHandle);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
251
gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp
Normal file
251
gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp
Normal file
@@ -0,0 +1,251 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-02 17:50:26
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 16:29:13
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp
|
||||||
|
*/
|
||||||
|
#include <string.h>
|
||||||
|
#include "GX40_gimbal_driver.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function sets the target position of a gimbal based on the input roll, pitch, and yaw values.
|
||||||
|
*
|
||||||
|
* @param pos The parameter "pos" is of type "AMOV_GIMBAL_POS_T". It is a structure that
|
||||||
|
* contains the roll, pitch, and yaw values of the gimbal position.
|
||||||
|
*
|
||||||
|
* @return a packed value of type uint32_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
|
{
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
targetPos[0] = (int16_t)(-pos.roll / 0.01f);
|
||||||
|
targetPos[1] = (int16_t)(-pos.pitch / 0.01f);
|
||||||
|
targetPos[2] = (int16_t)(-pos.yaw / 0.01f);
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
return pack(GX40::GIMBAL_CMD_MODE_EULER, nullptr, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function sets the gimbal speed based on the provided roll, pitch, and yaw values.
|
||||||
|
*
|
||||||
|
* @param speed The parameter "speed" is of type "AMOV_GIMBAL_POS_T". It is a structure
|
||||||
|
* that contains the roll, pitch, and yaw values of the gimbal speed.
|
||||||
|
*
|
||||||
|
* @return the result of the pack() function, which is of type uint32_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
|
{
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
targetPos[0] = (int16_t)(-speed.roll / 0.1f);
|
||||||
|
targetPos[1] = (int16_t)(-speed.pitch / 0.1f);
|
||||||
|
targetPos[2] = (int16_t)(-speed.yaw / 0.1f);
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
|
||||||
|
return pack(GX40::GIMBAL_CMD_MODE_FOLLOW, nullptr, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function sets the gimbal's home position to (0, 0, 0) and sends a command to the gimbal to go to
|
||||||
|
* the home position.
|
||||||
|
*
|
||||||
|
* @return the result of the pack() function call with the arguments GX40::GIMBAL_CMD_HOME, nullptr, and
|
||||||
|
* 0.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGimabalHome(void)
|
||||||
|
{
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
targetPos[0] = 0;
|
||||||
|
targetPos[1] = 0;
|
||||||
|
targetPos[2] = 0;
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
|
||||||
|
pack(GX40::GIMBAL_CMD_MODE_FOLLOW, nullptr, 0);
|
||||||
|
return pack(GX40::GIMBAL_CMD_HOME, nullptr, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `takePic` in the `GX40GimbalDriver` class takes a picture using the GX40 gimbal and
|
||||||
|
* returns the packed command.
|
||||||
|
*
|
||||||
|
* @return a uint32_t value.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::takePic(void)
|
||||||
|
{
|
||||||
|
uint8_t temp = 0X01;
|
||||||
|
|
||||||
|
return pack(GX40::GIMBAL_CMD_TAKEPIC, &temp, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `setVideo` toggles the video state of a gimbal driver and returns a packed command.
|
||||||
|
*
|
||||||
|
* @param newState The parameter `newState` is of type `AMOV_GIMBAL_VIDEO_T`, which is an
|
||||||
|
* enumeration representing the state of the video in the gimbal. It can have two possible values:
|
||||||
|
*
|
||||||
|
* @return the result of the `pack` function, which is a `uint32_t` value.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
|
{
|
||||||
|
uint8_t temp = 0X01;
|
||||||
|
|
||||||
|
mState.lock();
|
||||||
|
if (state.video == AMOV_GIMBAL_VIDEO_TAKE)
|
||||||
|
{
|
||||||
|
state.video = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
state.video = AMOV_GIMBAL_VIDEO_TAKE;
|
||||||
|
}
|
||||||
|
mState.unlock();
|
||||||
|
|
||||||
|
return pack(GX40::GIMBAL_CMD_TAKEPIC, &temp, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `attitudeCorrection` updates the state of a gimbal driver with position, velocity, and
|
||||||
|
* acceleration data.
|
||||||
|
*
|
||||||
|
* @param pos The "pos" parameter is of type "AMOV_GIMBAL_POS_T" and represents the current
|
||||||
|
* position of the gimbal. It likely contains information such as the pitch, yaw, and roll angles of
|
||||||
|
* the gimbal.
|
||||||
|
* @param seppd The parameter `seppd` stands for "Separate Pointing Device" and represents the velocity
|
||||||
|
* of the gimbal in separate axes (e.g., pitch, yaw, roll). It is of type
|
||||||
|
* `AMOV_GIMBAL_VELOCITY_T`.
|
||||||
|
* @param acc The "acc" parameter is of type "AMOV_GIMBAL_VELOCITY_T" and represents the
|
||||||
|
* acceleration of the gimbal.
|
||||||
|
* @param extenData The extenData parameter is a pointer to additional data that can be passed to the
|
||||||
|
* attitudeCorrection function. It can be used to provide any extra information or context that may be
|
||||||
|
* needed for the attitude correction calculation. The specific type and structure of the extenData is
|
||||||
|
* not provided in the code snippet,
|
||||||
|
*
|
||||||
|
* @return the size of the data being passed as arguments. The size is calculated by adding the sizes
|
||||||
|
* of the three types: sizeof(AMOV_GIMBAL_POS_T),
|
||||||
|
* sizeof(AMOV_GIMBAL_VELOCITY_T), and sizeof(AMOV_GIMBAL_VELOCITY_T).
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &seppd,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc,
|
||||||
|
void *extenData)
|
||||||
|
{
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
carrierPos = pos;
|
||||||
|
carrierSpeed = seppd;
|
||||||
|
carrierAcc = acc;
|
||||||
|
upDataTs = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch());
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
return sizeof(AMOV_GIMBAL_POS_T) + sizeof(AMOV_GIMBAL_VELOCITY_T) + sizeof(AMOV_GIMBAL_VELOCITY_T);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `extensionFuntions` takes a command as input, converts it to a specific format, and
|
||||||
|
* returns a 32-bit unsigned integer.
|
||||||
|
*
|
||||||
|
* @param cmd The parameter "cmd" is a void pointer, which means it can point to any type of data. In
|
||||||
|
* this case, it is being cast to a uint8_t pointer, which means it is expected to point to an array of
|
||||||
|
* uint8_t (8-bit unsigned integers).
|
||||||
|
*
|
||||||
|
* @return a value of type uint32_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::extensionFuntions(void *cmd)
|
||||||
|
{
|
||||||
|
uint8_t *temp = (uint8_t *)cmd;
|
||||||
|
return pack(temp[0], &temp[2], temp[1]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `setGimbalZoom` in the `GX40GimbalDriver` class sets the zoom level of a gimbal based on
|
||||||
|
* the specified zoom type and target rate.
|
||||||
|
*
|
||||||
|
* @param zoom The "zoom" parameter is of type AMOV_GIMBAL_ZOOM_T, which is an enumeration
|
||||||
|
* type. It represents the zoom action to be performed on the gimbal. The possible values for this
|
||||||
|
* parameter are:
|
||||||
|
* @param targetRate The targetRate parameter is a float value representing the desired zoom rate for
|
||||||
|
* the gimbal. It is used to control the zoom functionality of the gimbal.
|
||||||
|
*
|
||||||
|
* @return a value of type uint32_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
uint8_t temp[4];
|
||||||
|
uint8_t len = 0;
|
||||||
|
temp[1] = 0X01;
|
||||||
|
if (targetRate == 0.0f)
|
||||||
|
{
|
||||||
|
len = 1;
|
||||||
|
switch (zoom)
|
||||||
|
{
|
||||||
|
case AMOV_GIMBAL_ZOOM_IN:
|
||||||
|
temp[0] = GX40::GIMBAL_CMD_ZOMM_IN;
|
||||||
|
break;
|
||||||
|
case AMOV_GIMBAL_ZOOM_OUT:
|
||||||
|
temp[0] = GX40::GIMBAL_CMD_ZOOM_OUT;
|
||||||
|
break;
|
||||||
|
case AMOV_GIMBAL_ZOOM_STOP:
|
||||||
|
temp[0] = GX40::GIMBAL_CMD_ZOOM_STOP;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
len = 3;
|
||||||
|
temp[0] = GX40::GIMBAL_CMD_ZOOM;
|
||||||
|
int16_t targetTemp = (int16_t)(-targetRate / 0.1f);
|
||||||
|
temp[2] = (targetTemp >> 0) & 0XFF;
|
||||||
|
temp[3] = (targetTemp >> 8) & 0XFF;
|
||||||
|
}
|
||||||
|
|
||||||
|
return pack(temp[0], &temp[1], len);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function "setGimbalFocus" sets the focus of a gimbal by specifying the zoom level and target
|
||||||
|
* rate.
|
||||||
|
*
|
||||||
|
* @param zoom The zoom parameter is of type AMOV_GIMBAL_ZOOM_T, which is an enumeration
|
||||||
|
* type representing different zoom levels for the gimbal. It is used to specify the desired zoom level
|
||||||
|
* for the gimbal focus.
|
||||||
|
* @param targetRate The targetRate parameter is a float value representing the desired zoom rate for
|
||||||
|
* the gimbal.
|
||||||
|
*
|
||||||
|
* @return the result of the pack() function, which is of type uint32_t.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
uint8_t temp = 0X01;
|
||||||
|
|
||||||
|
return pack(GX40::GIMBAL_CMD_FOCUE, &temp, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function sets the GNSS information in the carrierGNSS struct and returns the size of the struct.
|
||||||
|
*
|
||||||
|
* @param lng The "lng" parameter represents the longitude value of the GNSS (Global Navigation
|
||||||
|
* Satellite System) information.
|
||||||
|
* @param lat The "lat" parameter represents the latitude value of the GNSS (Global Navigation
|
||||||
|
* Satellite System) information.
|
||||||
|
* @param alt The "alt" parameter represents the altitude value in meters.
|
||||||
|
* @param nState The parameter "nState" represents the state of the GNSS (Global Navigation Satellite
|
||||||
|
* System) information. It is of type uint32_t, which means it is an unsigned 32-bit integer. The
|
||||||
|
* specific values and their meanings for the "nState" parameter are not provided in the code snippet
|
||||||
|
* @param relAlt Relative altitude of the carrier (in meters)
|
||||||
|
*
|
||||||
|
* @return the size of the structure GX40::GIMBAL_SECONDARY_MASTER_FRAME_T.
|
||||||
|
*/
|
||||||
|
uint32_t GX40GimbalDriver::setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt)
|
||||||
|
{
|
||||||
|
carrierStateMutex.lock();
|
||||||
|
carrierGNSS.head = 0X01;
|
||||||
|
|
||||||
|
carrierGNSS.lng = lng / 1E-7;
|
||||||
|
carrierGNSS.lat = lat / 1E-7;
|
||||||
|
carrierGNSS.alt = alt / 1E-3;
|
||||||
|
|
||||||
|
carrierGNSS.relAlt = relAlt / 1E-3;
|
||||||
|
carrierGNSS.nState = nState;
|
||||||
|
|
||||||
|
carrierStateMutex.unlock();
|
||||||
|
return sizeof(GX40::GIMBAL_SECONDARY_MASTER_FRAME_T);
|
||||||
|
}
|
||||||
154
gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h
Normal file
154
gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h
Normal file
@@ -0,0 +1,154 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-10-20 16:08:13
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 16:28:54
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h
|
||||||
|
*/
|
||||||
|
#ifndef GX40_GIMBAL_STRUCT_H
|
||||||
|
#define GX40_GIMBAL_STRUCT_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
namespace GX40
|
||||||
|
{
|
||||||
|
#define XF_SEND_HEAD 0XE5A8
|
||||||
|
#define XF_RCV_HEAD 0X8A5E
|
||||||
|
#define XF_VERSION 0X00
|
||||||
|
#define XF_ANGLE_DPI 0.01f
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_IDLE,
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_HEAD,
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_LEN1,
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_LEN2,
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_VERSION,
|
||||||
|
GIMBAL_FRAME_PARSER_STATE_PAYLOAD,
|
||||||
|
} GIMBAL_FRAME_PARSER_STATE_T;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
GIMBAL_CMD_NOP = 0X00,
|
||||||
|
GIMBAL_CMD_CAL = 0X01,
|
||||||
|
GIMBAL_CMD_HOME = 0X03,
|
||||||
|
GIMBAL_CMD_MODE_FPV = 0X10,
|
||||||
|
GIMBAL_CMD_MODE_LOCK = 0X11,
|
||||||
|
GIMBAL_CMD_MODE_FOLLOW = 0X12,
|
||||||
|
GIMBAL_CMD_MODE_OVERLOCK = 0X13,
|
||||||
|
GIMBAL_CMD_MODE_EULER = 0X14,
|
||||||
|
GIMBAL_CMD_MODE_WATCH_POS = 0X15,
|
||||||
|
GIMBAL_CMD_MODE_WATCH = 0X16,
|
||||||
|
GIMBAL_CMD_MODE_TRACK = 0X17,
|
||||||
|
GIMBAL_CMD_MODE_MOVE = 0X1A,
|
||||||
|
GIMBAL_CMD_MODE_MOVE_TRACK = 0X1B,
|
||||||
|
GIMBAL_CMD_TAKEPIC = 0X20,
|
||||||
|
GIMBAL_CMD_TAKEVIDEO = 0X21,
|
||||||
|
GIMBAL_CMD_ZOOM_OUT = 0X22,
|
||||||
|
GIMBAL_CMD_ZOMM_IN = 0X23,
|
||||||
|
GIMBAL_CMD_ZOOM_STOP = 0X24,
|
||||||
|
GIMBAL_CMD_ZOOM = 0X25,
|
||||||
|
GIMBAL_CMD_FOCUE = 0X26,
|
||||||
|
GIMBAL_CMD_VIDEO_MODE = 0X2A,
|
||||||
|
GIMBAL_CMD_NIGHT = 0X2B,
|
||||||
|
GIMBAL_CMD_OSD = 0X73,
|
||||||
|
GIMBAL_CMD_FIX_MODE = 0X74,
|
||||||
|
GIMBAL_CMD_LIGHT = 0X80,
|
||||||
|
GIMBAL_CMD_TAKE_DISTANCE = 0X81,
|
||||||
|
} GIMBAL_CMD_T;
|
||||||
|
|
||||||
|
#pragma pack(1)
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
union
|
||||||
|
{
|
||||||
|
uint8_t u8[2];
|
||||||
|
uint16_t u16;
|
||||||
|
} head;
|
||||||
|
union
|
||||||
|
{
|
||||||
|
uint8_t u8[2];
|
||||||
|
uint16_t u16;
|
||||||
|
} lenght;
|
||||||
|
uint8_t version;
|
||||||
|
uint8_t primaryData[32];
|
||||||
|
uint8_t secondaryData[32];
|
||||||
|
uint8_t otherData[32];
|
||||||
|
union
|
||||||
|
{
|
||||||
|
uint8_t u8[2];
|
||||||
|
uint16_t u16;
|
||||||
|
} crc16;
|
||||||
|
} GIMBAL_FRAME_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
int16_t roll;
|
||||||
|
int16_t pitch;
|
||||||
|
int16_t yaw;
|
||||||
|
uint8_t state;
|
||||||
|
int16_t selfRoll;
|
||||||
|
int16_t selfPitch;
|
||||||
|
uint16_t selfYaw;
|
||||||
|
int16_t accN;
|
||||||
|
int16_t accE;
|
||||||
|
int16_t accUp;
|
||||||
|
int16_t speedN;
|
||||||
|
int16_t speedE;
|
||||||
|
int16_t speedUp;
|
||||||
|
uint8_t secondaryFlag;
|
||||||
|
uint8_t reserve[6];
|
||||||
|
} GIMBAL_PRIMARY_MASTER_FRAME_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t workMode;
|
||||||
|
uint16_t state;
|
||||||
|
int16_t offsetX;
|
||||||
|
int16_t offsetY;
|
||||||
|
uint16_t motorRoll;
|
||||||
|
uint16_t motorPitch;
|
||||||
|
uint16_t motorYaw;
|
||||||
|
int16_t roll;
|
||||||
|
int16_t pitch;
|
||||||
|
uint16_t yaw;
|
||||||
|
int16_t speedRoll;
|
||||||
|
int16_t speedPitch;
|
||||||
|
int16_t speedYaw;
|
||||||
|
uint8_t reserve[7];
|
||||||
|
} GIMBAL_PRIMARY_SLAVE_FRAME_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t head;
|
||||||
|
int32_t lng;
|
||||||
|
int32_t lat;
|
||||||
|
int32_t alt;
|
||||||
|
uint8_t nState;
|
||||||
|
uint32_t GPSms;
|
||||||
|
int32_t GPSweeks;
|
||||||
|
int32_t relAlt;
|
||||||
|
uint8_t reserve[8];
|
||||||
|
} GIMBAL_SECONDARY_MASTER_FRAME_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t head;
|
||||||
|
uint8_t versionHW;
|
||||||
|
uint8_t versionSoft;
|
||||||
|
uint8_t type;
|
||||||
|
uint16_t error;
|
||||||
|
int32_t targetDistance;
|
||||||
|
int32_t targetLng;
|
||||||
|
int32_t targetLat;
|
||||||
|
int32_t targetAlt;
|
||||||
|
uint16_t camera1Zoom;
|
||||||
|
uint16_t camera2Zoom;
|
||||||
|
uint8_t reserve[6];
|
||||||
|
} GIMBAL_SECONDARY_SLAVE_FRAME_T;
|
||||||
|
#pragma pack()
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
@@ -3,12 +3,11 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-03-23 17:24:23
|
* @LastEditTime: 2023-12-05 16:28:29
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_crc32.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h
|
||||||
*/
|
*/
|
||||||
#ifndef Q10F_GIMBAL_CRC32_H
|
#ifndef Q10F_GIMBAL_CRC32_H
|
||||||
#define Q10F_GIMBAL_CRC32_H
|
#define Q10F_GIMBAL_CRC32_H
|
||||||
|
|
||||||
namespace Q10f
|
namespace Q10f
|
||||||
{
|
{
|
||||||
static inline unsigned char CheckSum(unsigned char *pData, unsigned short Lenght)
|
static inline unsigned char CheckSum(unsigned char *pData, unsigned short Lenght)
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:06
|
* @Date: 2022-10-27 18:10:06
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-07-24 12:03:44
|
* @LastEditTime: 2023-12-05 17:23:15
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_driver.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp
|
||||||
*/
|
*/
|
||||||
#include "Q10f_gimbal_driver.h"
|
#include "Q10f_gimbal_driver.h"
|
||||||
#include "Q10f_gimbal_crc32.h"
|
#include "Q10f_gimbal_crc32.h"
|
||||||
@@ -86,7 +86,7 @@ void Q10fGimbalDriver::convert(void *buf)
|
|||||||
state.rel.pitch = tempPos->pitchStatorRotorAngle * Q10F_SCALE_FACTOR_SPEED;
|
state.rel.pitch = tempPos->pitchStatorRotorAngle * Q10F_SCALE_FACTOR_SPEED;
|
||||||
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
updateGimbalStateCallback(state.rel.roll, state.rel.pitch, state.rel.yaw,
|
||||||
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
state.abs.roll, state.abs.pitch, state.abs.yaw,
|
||||||
state.fov.x, state.fov.y);
|
state.fov.x, state.fov.y, updataCaller);
|
||||||
mState.unlock();
|
mState.unlock();
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|||||||
@@ -3,19 +3,18 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-28 12:24:21
|
* @Date: 2022-10-28 12:24:21
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-03-28 17:01:00
|
* @LastEditTime: 2023-12-05 16:27:45
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_driver.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h
|
||||||
*/
|
*/
|
||||||
#include "../amov_gimbal.h"
|
#ifndef __Q10F_DRIVER_H
|
||||||
|
#define __Q10F_DRIVER_H
|
||||||
|
|
||||||
#include "../amov_gimbal_private.h"
|
#include "../amov_gimbal_private.h"
|
||||||
#include "Q10f_gimbal_struct.h"
|
#include "Q10f_gimbal_struct.h"
|
||||||
#include <mutex>
|
#include <mutex>
|
||||||
#include <malloc.h>
|
#include <malloc.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#ifndef __Q10F_DRIVER_H
|
|
||||||
#define __Q10F_DRIVER_H
|
|
||||||
|
|
||||||
class Q10fGimbalDriver : protected amovGimbal::amovGimbalBase
|
class Q10fGimbalDriver : protected amovGimbal::amovGimbalBase
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
@@ -29,16 +28,16 @@ private:
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
// funtions
|
// funtions
|
||||||
uint32_t setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos);
|
uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
uint32_t setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed);
|
uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
uint32_t setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed);
|
uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
||||||
uint32_t setGimabalHome(void);
|
uint32_t setGimabalHome(void);
|
||||||
|
|
||||||
uint32_t setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
uint32_t setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
|
||||||
uint32_t takePic(void);
|
uint32_t takePic(void);
|
||||||
uint32_t setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState);
|
uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
|
||||||
// builds
|
// builds
|
||||||
static amovGimbal::amovGimbalBase *creat(amovGimbal::IOStreamBase *_IO)
|
static amovGimbal::amovGimbalBase *creat(amovGimbal::IOStreamBase *_IO)
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-03-02 10:00:52
|
* @Date: 2023-03-02 10:00:52
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-07-24 14:22:57
|
* @LastEditTime: 2023-12-05 16:27:39
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_funtion.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp
|
||||||
*/
|
*/
|
||||||
#include "Q10f_gimbal_driver.h"
|
#include "Q10f_gimbal_driver.h"
|
||||||
#include "Q10f_gimbal_crc32.h"
|
#include "Q10f_gimbal_crc32.h"
|
||||||
@@ -17,7 +17,7 @@
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t Q10fGimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos)
|
uint32_t Q10fGimbalDriver::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
{
|
{
|
||||||
Q10f::GIMBAL_SET_POS_MSG_T temp;
|
Q10f::GIMBAL_SET_POS_MSG_T temp;
|
||||||
temp.modeR = Q10f::GIMBAL_CMD_POS_MODE_ANGLE_SPEED;
|
temp.modeR = Q10f::GIMBAL_CMD_POS_MODE_ANGLE_SPEED;
|
||||||
@@ -41,7 +41,7 @@ uint32_t Q10fGimbalDriver::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &po
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t Q10fGimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed)
|
uint32_t Q10fGimbalDriver::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
{
|
{
|
||||||
Q10f::GIMBAL_SET_POS_MSG_T temp;
|
Q10f::GIMBAL_SET_POS_MSG_T temp;
|
||||||
temp.modeR = Q10f::GIMBAL_CMD_POS_MODE_SPEED;
|
temp.modeR = Q10f::GIMBAL_CMD_POS_MODE_SPEED;
|
||||||
@@ -64,7 +64,7 @@ uint32_t Q10fGimbalDriver::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the buffer.
|
* @return The return value is the number of bytes written to the buffer.
|
||||||
*/
|
*/
|
||||||
uint32_t Q10fGimbalDriver::setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed)
|
uint32_t Q10fGimbalDriver::setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed)
|
||||||
{
|
{
|
||||||
state.maxFollow.pitch = followSpeed.pitch / 0.1220740379f;
|
state.maxFollow.pitch = followSpeed.pitch / 0.1220740379f;
|
||||||
state.maxFollow.roll = followSpeed.roll / 0.1220740379f;
|
state.maxFollow.roll = followSpeed.roll / 0.1220740379f;
|
||||||
@@ -108,25 +108,25 @@ uint32_t Q10fGimbalDriver::takePic(void)
|
|||||||
*
|
*
|
||||||
* @return The return value is the number of bytes written to the serial port.
|
* @return The return value is the number of bytes written to the serial port.
|
||||||
*/
|
*/
|
||||||
uint32_t Q10fGimbalDriver::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState)
|
uint32_t Q10fGimbalDriver::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
{
|
{
|
||||||
uint8_t cmd[2] = {0X01, 0XFF};
|
uint8_t cmd[2] = {0X01, 0XFF};
|
||||||
|
|
||||||
if (newState == amovGimbal::AMOV_GIMBAL_VIDEO_TAKE)
|
if (newState == AMOV_GIMBAL_VIDEO_TAKE)
|
||||||
{
|
{
|
||||||
cmd[0] = 0X02;
|
cmd[0] = 0X02;
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_TAKE;
|
state.video = AMOV_GIMBAL_VIDEO_TAKE;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
cmd[0] = 0X03;
|
cmd[0] = 0X03;
|
||||||
state.video = amovGimbal::AMOV_GIMBAL_VIDEO_OFF;
|
state.video = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
}
|
}
|
||||||
|
|
||||||
return pack(Q10f::GIMBAL_CMD_CAMERA, (uint8_t *)cmd, sizeof(cmd));
|
return pack(Q10f::GIMBAL_CMD_CAMERA, (uint8_t *)cmd, sizeof(cmd));
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t Q10fGimbalDriver::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
uint32_t Q10fGimbalDriver::setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
{
|
{
|
||||||
uint8_t cmd[5] = {0X00, 0X00, 0X00, 0X00, 0XFF};
|
uint8_t cmd[5] = {0X00, 0X00, 0X00, 0X00, 0XFF};
|
||||||
if (targetRate == 0.0f)
|
if (targetRate == 0.0f)
|
||||||
@@ -134,13 +134,13 @@ uint32_t Q10fGimbalDriver::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, fl
|
|||||||
cmd[1] = 0XFF;
|
cmd[1] = 0XFF;
|
||||||
switch (zoom)
|
switch (zoom)
|
||||||
{
|
{
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_IN:
|
case AMOV_GIMBAL_ZOOM_IN:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_IN;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_IN;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_OUT:
|
case AMOV_GIMBAL_ZOOM_OUT:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_OUT;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_OUT;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_STOP:
|
case AMOV_GIMBAL_ZOOM_STOP:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_STOP;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_STOP;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@@ -159,18 +159,18 @@ uint32_t Q10fGimbalDriver::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, fl
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t Q10fGimbalDriver::setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
uint32_t Q10fGimbalDriver::setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
{
|
{
|
||||||
uint8_t cmd[2] = {0X00, 0XFF};
|
uint8_t cmd[2] = {0X00, 0XFF};
|
||||||
switch (zoom)
|
switch (zoom)
|
||||||
{
|
{
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_IN:
|
case AMOV_GIMBAL_ZOOM_IN:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_IN;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_IN;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_OUT:
|
case AMOV_GIMBAL_ZOOM_OUT:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_OUT;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_OUT;
|
||||||
break;
|
break;
|
||||||
case amovGimbal::AMOV_GIMBAL_ZOOM_STOP:
|
case AMOV_GIMBAL_ZOOM_STOP:
|
||||||
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_STOP;
|
cmd[0] = Q10f::GIMBAL_CMD_ZOOM_STOP;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2022-10-27 18:10:07
|
* @Date: 2022-10-27 18:10:07
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-07-24 11:51:59
|
* @LastEditTime: 2023-12-05 16:27:27
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_struct.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h
|
||||||
*/
|
*/
|
||||||
#ifndef Q10F_GIMBAL_STRUCT_H
|
#ifndef Q10F_GIMBAL_STRUCT_H
|
||||||
#define Q10F_GIMBAL_STRUCT_H
|
#define Q10F_GIMBAL_STRUCT_H
|
||||||
|
|||||||
111
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal.h
Executable file
111
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal.h
Executable file
@@ -0,0 +1,111 @@
|
|||||||
|
/*
|
||||||
|
* @Description: External interface of amov gimbals
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2022-10-27 18:34:26
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 17:37:09
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amovGimbal/amov_gimbal.h
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef AMOV_GIMBAL_H
|
||||||
|
#define AMOV_GIMBAL_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "amov_gimbal_struct.h"
|
||||||
|
|
||||||
|
namespace amovGimbal
|
||||||
|
{
|
||||||
|
#define IN
|
||||||
|
#define OUT
|
||||||
|
#define SET
|
||||||
|
|
||||||
|
#ifndef MAX_QUEUE_SIZE
|
||||||
|
#define MAX_QUEUE_SIZE 100
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static inline void idleCallback(double frameAngleRoll, double frameAnglePitch, double frameAngleYaw,
|
||||||
|
double imuAngleRoll, double imuAnglePitch, double imuAngleYaw,
|
||||||
|
double fovX, double fovY, void *caller)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
static inline void idleMsgCallback(void *msg, void *caller)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
// Control data input and output
|
||||||
|
class IOStreamBase
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
IOStreamBase() {}
|
||||||
|
virtual ~IOStreamBase() {}
|
||||||
|
|
||||||
|
virtual bool open() = 0;
|
||||||
|
virtual bool close() = 0;
|
||||||
|
virtual bool isOpen() = 0;
|
||||||
|
virtual bool isBusy() = 0;
|
||||||
|
// These two functions need to be thread-safe
|
||||||
|
virtual uint32_t inPutBytes(IN uint8_t *byte) = 0;
|
||||||
|
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght) = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
class gimbal
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
std::string typeName;
|
||||||
|
// Instantiated device handle
|
||||||
|
void *devHandle;
|
||||||
|
|
||||||
|
public:
|
||||||
|
static void inBytesCallback(uint8_t *pData, uint32_t len, gimbal *handle);
|
||||||
|
// Protocol stack function items
|
||||||
|
void startStack(void);
|
||||||
|
void parserAuto(pAmovGimbalStateInvoke callback = idleCallback, void *caller = nullptr);
|
||||||
|
void setParserCallback(pAmovGimbalStateInvoke callback, void *caller = nullptr);
|
||||||
|
void setMsgCallback(pAmovGimbalMsgInvoke callback, void *caller = nullptr);
|
||||||
|
void setRcvBytes(pAmovGimbalInputBytesInvoke callbaclk, void *caller = nullptr);
|
||||||
|
void setSendBytes(pAmovGimbalOutputBytesInvoke callbaclk, void *caller = nullptr);
|
||||||
|
AMOV_GIMBAL_STATE_T getGimabalState(void);
|
||||||
|
|
||||||
|
// non-block functions
|
||||||
|
uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
|
uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
|
uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
||||||
|
|
||||||
|
uint32_t setGimabalHome(void);
|
||||||
|
uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
uint32_t setGimbalROI(const AMOV_GIMBAL_ROI_T area);
|
||||||
|
uint32_t takePic(void);
|
||||||
|
uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
uint32_t attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
||||||
|
uint32_t attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &seppd,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
||||||
|
uint32_t setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt);
|
||||||
|
uint32_t extensionFuntions(void *cmd);
|
||||||
|
|
||||||
|
// block functions
|
||||||
|
bool setGimbalPosBlock(const AMOV_GIMBAL_POS_T &pos);
|
||||||
|
bool setGimabalHomeBlock(void);
|
||||||
|
bool setGimbalZoomBlock(float targetRate);
|
||||||
|
bool takePicBlock(void);
|
||||||
|
bool calibrationBlock(void);
|
||||||
|
|
||||||
|
std::string name()
|
||||||
|
{
|
||||||
|
return typeName;
|
||||||
|
}
|
||||||
|
|
||||||
|
gimbal(const std::string &type, IOStreamBase *_IO,
|
||||||
|
uint32_t _self = 0x02, uint32_t _remote = 0X80);
|
||||||
|
|
||||||
|
~gimbal();
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif
|
||||||
55
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_c.h
Normal file
55
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_c.h
Normal file
@@ -0,0 +1,55 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-24 16:01:22
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-06 11:35:58
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_c.h
|
||||||
|
*/
|
||||||
|
#ifndef AMOV_GIMBAL_C_H
|
||||||
|
#define AMOV_GIMBAL_C_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "amov_gimbal_struct.h"
|
||||||
|
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
// initialization funtions
|
||||||
|
void amovGimbalCreat(char *type, uint32_t selfId, uint32_t gimbalId, void *handle);
|
||||||
|
void amovGimbalInBytesCallback(uint8_t *pData, uint32_t len, void *handle);
|
||||||
|
void amovGimbalSetRcvBytes(pAmovGimbalInputBytesInvoke callbaclk, void *handle, void *caller);
|
||||||
|
void amovGimbalSetSendBytes(pAmovGimbalOutputBytesInvoke callbaclk, void *handle, void *caller);
|
||||||
|
void amovGimbalChangeStateCallback(pAmovGimbalStateInvoke callback, void *handle, void *caller);
|
||||||
|
void amovGimbalSetMsgCallback(pAmovGimbalMsgInvoke callback, void *handle, void *caller);
|
||||||
|
void amovGimbalStart(pAmovGimbalStateInvoke callback, void *handle, void *caller);
|
||||||
|
|
||||||
|
// non-block functions
|
||||||
|
uint32_t amovGimbalSetGimabalPos(AMOV_GIMBAL_POS_T *pos, void *handle);
|
||||||
|
uint32_t amovGimbalSetGimabalSpeed(AMOV_GIMBAL_POS_T *speed, void *handle);
|
||||||
|
uint32_t amovGimbalSetGimabalFollowSpeed(AMOV_GIMBAL_POS_T *followSpeed, void *handle);
|
||||||
|
uint32_t amovGimbalSetGimabalHome(void *handle);
|
||||||
|
uint32_t amovGimbalSetGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate, void *handle);
|
||||||
|
uint32_t amovGimbalSetGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate, void *handle);
|
||||||
|
uint32_t amovGimbalSetGimbalROI(AMOV_GIMBAL_ROI_T *area, void *handle);
|
||||||
|
uint32_t amovGimbalTakePic(void *handle);
|
||||||
|
uint32_t amovGimbalSetVideo(AMOV_GIMBAL_VIDEO_T newState, void *handle);
|
||||||
|
uint32_t amovGimbalAttitudeCorrectionQ(AMOV_GIMBAL_QUATERNION_T *quaterion,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *speed,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *acc, void *extenData, void *handle);
|
||||||
|
uint32_t amovGimbalAttitudeCorrectionE(AMOV_GIMBAL_POS_T *pos,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *speed,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *acc, void *extenData, void *handle);
|
||||||
|
uint32_t amovGimbalSetGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt, void *handle);
|
||||||
|
uint32_t amovGimbalExtensionFuntions(void *cmd, void *handle);
|
||||||
|
void getGimabalState(AMOV_GIMBAL_STATE_T *state, void *handle);
|
||||||
|
void getGimbalType(char *type, void *handle);
|
||||||
|
|
||||||
|
// block functions
|
||||||
|
bool amovGimbalSetGimbalPosBlock(AMOV_GIMBAL_POS_T *pos, void *handle);
|
||||||
|
bool amovGimbalSetGimabalHomeBlock(void *handle);
|
||||||
|
bool amovGimbalSetGimbalZoomBlock(float targetRate, void *handle);
|
||||||
|
bool amovGimbalTakePicBlock(void *handle);
|
||||||
|
bool amovGimbalCalibrationBlock(void *handle);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
102
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_struct.h
Executable file
102
gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_struct.h
Executable file
@@ -0,0 +1,102 @@
|
|||||||
|
/*
|
||||||
|
* @Description: Common Data Structures of gimbal
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2022-10-31 11:56:43
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 17:03:02
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amovGimbal/amov_gimbal_struct.h
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#ifndef __AMOV_GIMABL_STRUCT_H
|
||||||
|
#define __AMOV_GIMABL_STRUCT_H
|
||||||
|
|
||||||
|
typedef void (*pAmovGimbalStateInvoke)(double frameAngleRoll, double frameAnglePitch, double frameAngleYaw,
|
||||||
|
double imuAngleRoll, double imuAnglePitch, double imuAngleYaw,
|
||||||
|
double fovX, double fovY, void *caller);
|
||||||
|
typedef void (*pAmovGimbalMsgInvoke)(void *msg, void *caller);
|
||||||
|
typedef uint32_t (*pAmovGimbalInputBytesInvoke)(uint8_t *pData, void *caller);
|
||||||
|
typedef uint32_t (*pAmovGimbalOutputBytesInvoke)(uint8_t *pData, uint32_t len, void *caller);
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_FPV = 0X10,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_LOCK = 0X11,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_FOLLOW = 0X12,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_OVERLOOK = 0X13,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_EULER = 0X14,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_WATCH = 0X16,
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_TRACK = 0X17,
|
||||||
|
} AMOV_GIMBAL_SERVO_MODE_T;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
AMOV_GIMBAL_CAMERA_FLAG_INVERSION = 0X1000,
|
||||||
|
AMOV_GIMBAL_CAMERA_FLAG_IR = 0X0200,
|
||||||
|
AMOV_GIMBAL_CAMERA_FLAG_RF = 0X0100,
|
||||||
|
AMOV_GIMBAL_CAMERA_FLAG_LOCK = 0X0001,
|
||||||
|
} AMOV_GIMBAL_CAMERA_FLAG_T;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
AMOV_GIMBAL_VIDEO_TAKE,
|
||||||
|
AMOV_GIMBAL_VIDEO_OFF
|
||||||
|
} AMOV_GIMBAL_VIDEO_T;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
AMOV_GIMBAL_ZOOM_IN,
|
||||||
|
AMOV_GIMBAL_ZOOM_OUT,
|
||||||
|
AMOV_GIMBAL_ZOOM_STOP
|
||||||
|
} AMOV_GIMBAL_ZOOM_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
double yaw;
|
||||||
|
double roll;
|
||||||
|
double pitch;
|
||||||
|
} AMOV_GIMBAL_POS_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
double x;
|
||||||
|
double y;
|
||||||
|
} AMOV_GIMBAL_FOV_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
AMOV_GIMBAL_SERVO_MODE_T workMode;
|
||||||
|
AMOV_GIMBAL_CAMERA_FLAG_T cameraFlag;
|
||||||
|
AMOV_GIMBAL_VIDEO_T video;
|
||||||
|
AMOV_GIMBAL_POS_T abs;
|
||||||
|
AMOV_GIMBAL_POS_T rel;
|
||||||
|
AMOV_GIMBAL_POS_T relSpeed;
|
||||||
|
AMOV_GIMBAL_POS_T maxFollow;
|
||||||
|
AMOV_GIMBAL_FOV_T fov;
|
||||||
|
} AMOV_GIMBAL_STATE_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t centreX;
|
||||||
|
uint32_t centreY;
|
||||||
|
uint32_t hight;
|
||||||
|
uint32_t width;
|
||||||
|
} AMOV_GIMBAL_ROI_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
double q0;
|
||||||
|
double q1;
|
||||||
|
double q2;
|
||||||
|
double q3;
|
||||||
|
} AMOV_GIMBAL_QUATERNION_T;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
double x; // or N
|
||||||
|
double y; // or E
|
||||||
|
double z; // or UP
|
||||||
|
} AMOV_GIMBAL_VELOCITY_T;
|
||||||
|
|
||||||
|
#endif
|
||||||
@@ -1,328 +0,0 @@
|
|||||||
/*
|
|
||||||
* @Description:
|
|
||||||
* @Author: L LC @amov
|
|
||||||
* @Date: 2022-10-28 11:54:11
|
|
||||||
* @LastEditors: L LC @amov
|
|
||||||
* @LastEditTime: 2023-08-17 11:57:11
|
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/amov_gimbal.cpp
|
|
||||||
*/
|
|
||||||
|
|
||||||
// #include "amov_gimbal.h"
|
|
||||||
#include "amov_gimbal_private.h"
|
|
||||||
#include "g1_gimbal_driver.h"
|
|
||||||
#include "Q10f_gimbal_driver.h"
|
|
||||||
#include "AT10_gimbal_driver.h"
|
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#include <thread>
|
|
||||||
#include <map>
|
|
||||||
#include <iterator>
|
|
||||||
|
|
||||||
#define MAX_PACK_SIZE 280
|
|
||||||
typedef enum
|
|
||||||
{
|
|
||||||
AMOV_GIMBAL_TYPE_NULL,
|
|
||||||
AMOV_GIMBAL_TYPE_G1 = 1,
|
|
||||||
AMOV_GIMBAL_TYPE_G2,
|
|
||||||
AMOV_GIMBAL_TYPE_Q10,
|
|
||||||
AMOV_GIMBAL_TYPE_AT10,
|
|
||||||
} AMOV_GIMBAL_TYPE_T;
|
|
||||||
|
|
||||||
namespace amovGimbal
|
|
||||||
{
|
|
||||||
typedef amovGimbal::amovGimbalBase *(*createCallback)(amovGimbal::IOStreamBase *_IO);
|
|
||||||
typedef std::map<std::string, createCallback> callbackMap;
|
|
||||||
std::map<std::string, AMOV_GIMBAL_TYPE_T> amovGimbalTypeList =
|
|
||||||
{
|
|
||||||
{"G1", AMOV_GIMBAL_TYPE_G1},
|
|
||||||
{"Q10f", AMOV_GIMBAL_TYPE_Q10},
|
|
||||||
{"AT10", AMOV_GIMBAL_TYPE_AT10}};
|
|
||||||
|
|
||||||
callbackMap amovGimbals =
|
|
||||||
{
|
|
||||||
{"G1", g1GimbalDriver::creat},
|
|
||||||
{"Q10f", Q10fGimbalDriver::creat},
|
|
||||||
{"AT10", AT10GimbalDriver::creat}};
|
|
||||||
}
|
|
||||||
|
|
||||||
/* The amovGimbalCreator class is a factory class that creates an instance of the amovGimbal class */
|
|
||||||
// Factory used to create the gimbal instance
|
|
||||||
class amovGimbalCreator
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
static amovGimbal::amovGimbalBase *createAmovGimbal(const std::string &type, amovGimbal::IOStreamBase *_IO)
|
|
||||||
{
|
|
||||||
amovGimbal::callbackMap::iterator temp = amovGimbal::amovGimbals.find(type);
|
|
||||||
|
|
||||||
if (temp != amovGimbal::amovGimbals.end())
|
|
||||||
{
|
|
||||||
return (temp->second)(_IO);
|
|
||||||
}
|
|
||||||
std::cout << type << " is Unsupported device type!" << std::endl;
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
amovGimbalCreator()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
static amovGimbalCreator *pInstance;
|
|
||||||
static amovGimbalCreator *getInstance()
|
|
||||||
{
|
|
||||||
if (pInstance == NULL)
|
|
||||||
{
|
|
||||||
pInstance = new amovGimbalCreator();
|
|
||||||
}
|
|
||||||
return pInstance;
|
|
||||||
}
|
|
||||||
|
|
||||||
~amovGimbalCreator();
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This is a constructor for the amovGimbalBase class that initializes its parent classes with an
|
|
||||||
* IOStreamBase object.
|
|
||||||
*
|
|
||||||
* @param _IO _IO is a pointer to an object of type amovGimbal::IOStreamBase, which is the base class
|
|
||||||
* for input/output streams used by the amovGimbal class. This parameter is passed to the constructor
|
|
||||||
* of amovGimbalBase, which is a derived class of I
|
|
||||||
*/
|
|
||||||
amovGimbal::amovGimbalBase::amovGimbalBase(amovGimbal::IOStreamBase *_IO) : amovGimbal::IamovGimbalBase(), amovGimbal::PamovGimbalBase(_IO)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* The function is a destructor that sleeps for 50 milliseconds and closes an IO object.
|
|
||||||
*/
|
|
||||||
amovGimbal::amovGimbalBase::~amovGimbalBase()
|
|
||||||
{
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
|
||||||
IO->close();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This function retrieves a packet from a ring buffer queue and returns a boolean value indicating
|
|
||||||
* whether the operation was successful or not.
|
|
||||||
*
|
|
||||||
* @param void void is a keyword in C++ that represents the absence of a type. In this function, it is
|
|
||||||
* used to indicate that the function does not return any value.
|
|
||||||
*
|
|
||||||
* @return a boolean value, which indicates whether or not a data packet was successfully retrieved
|
|
||||||
* from a ring buffer queue.
|
|
||||||
*/
|
|
||||||
bool amovGimbal::amovGimbalBase::getRxPack(OUT void *pack)
|
|
||||||
{
|
|
||||||
bool state = false;
|
|
||||||
state = rxQueue->outCell(pack);
|
|
||||||
return state;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This function sends data from a buffer to an output device if it is not busy and open.
|
|
||||||
*/
|
|
||||||
void amovGimbal::amovGimbalBase::send(void)
|
|
||||||
{
|
|
||||||
uint8_t tempBuffer[MAX_PACK_SIZE];
|
|
||||||
|
|
||||||
if (!IO->isBusy() && IO->isOpen())
|
|
||||||
{
|
|
||||||
bool state = false;
|
|
||||||
|
|
||||||
state = txQueue->outCell(&tempBuffer);
|
|
||||||
|
|
||||||
if (state)
|
|
||||||
{
|
|
||||||
IO->outPutBytes((uint8_t *)&tempBuffer, calPackLen(tempBuffer));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* "If the input byte is available, then parse it."
|
|
||||||
*
|
|
||||||
* The function is a loop that runs forever. It calls the IO->inPutByte() function to get a byte from
|
|
||||||
* the serial port. If the byte is available, then it calls the parser() function to parse the byte
|
|
||||||
*/
|
|
||||||
void amovGimbal::amovGimbalBase::parserLoop(void)
|
|
||||||
{
|
|
||||||
uint8_t temp;
|
|
||||||
|
|
||||||
while (1)
|
|
||||||
{
|
|
||||||
if (IO->inPutByte(&temp))
|
|
||||||
{
|
|
||||||
parser(temp);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::amovGimbalBase::sendLoop(void)
|
|
||||||
{
|
|
||||||
while (1)
|
|
||||||
{
|
|
||||||
send();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::amovGimbalBase::mainLoop(void)
|
|
||||||
{
|
|
||||||
uint8_t tempBuffer[MAX_PACK_SIZE];
|
|
||||||
|
|
||||||
while (1)
|
|
||||||
{
|
|
||||||
if (getRxPack(tempBuffer))
|
|
||||||
{
|
|
||||||
msgCustomCallback(tempBuffer);
|
|
||||||
convert(tempBuffer);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::amovGimbalBase::stackStart(void)
|
|
||||||
{
|
|
||||||
if (!this->IO->isOpen())
|
|
||||||
{
|
|
||||||
this->IO->open();
|
|
||||||
}
|
|
||||||
std::thread parserLoop(&amovGimbalBase::parserLoop, this);
|
|
||||||
std::thread sendLoop(&amovGimbalBase::sendLoop, this);
|
|
||||||
parserLoop.detach();
|
|
||||||
sendLoop.detach();
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* It starts two threads, one for reading data from the serial port and one for sending data to the
|
|
||||||
* serial port
|
|
||||||
*/
|
|
||||||
void amovGimbal::gimbal::startStack(void)
|
|
||||||
{
|
|
||||||
((amovGimbalBase *)(this->dev))->stackStart();
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::gimbal::setParserCallback(amovGimbal::pStateInvoke callback)
|
|
||||||
{
|
|
||||||
((amovGimbalBase *)(this->dev))->updateGimbalStateCallback = callback;
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::amovGimbalBase::parserStart(pStateInvoke callback)
|
|
||||||
{
|
|
||||||
this->updateGimbalStateCallback = callback;
|
|
||||||
|
|
||||||
std::thread mainLoop(&amovGimbalBase::mainLoop, this);
|
|
||||||
|
|
||||||
mainLoop.detach();
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* The function creates a thread that runs the mainLoop function
|
|
||||||
*/
|
|
||||||
void amovGimbal::gimbal::parserAuto(pStateInvoke callback)
|
|
||||||
{
|
|
||||||
((amovGimbalBase *)(this->dev))->parserStart(callback);
|
|
||||||
}
|
|
||||||
|
|
||||||
void amovGimbal::gimbal::setMsgCallback(pMsgInvoke callback)
|
|
||||||
{
|
|
||||||
((amovGimbalBase *)(this->dev))->msgCustomCallback = callback;
|
|
||||||
}
|
|
||||||
|
|
||||||
amovGimbal::AMOV_GIMBAL_STATE_T amovGimbal::gimbal::getGimabalState(void)
|
|
||||||
{
|
|
||||||
((amovGimbalBase *)(this->dev))->mState.lock();
|
|
||||||
AMOV_GIMBAL_STATE_T temp = ((amovGimbalBase *)(this->dev))->state;
|
|
||||||
((amovGimbalBase *)(this->dev))->mState.unlock();
|
|
||||||
return temp;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default implementation of interface functions, not pure virtual functions for ease of extension.
|
|
||||||
*/
|
|
||||||
void amovGimbal::IamovGimbalBase::nodeSet(SET uint32_t _self, SET uint32_t _remote)
|
|
||||||
{
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimabalPos(const amovGimbal::AMOV_GIMBAL_POS_T &pos)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimabalFollowSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &followSpeed)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimabalHome(void)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setGimbalROI(const amovGimbal::AMOV_GIMBAL_ROI_T area)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::takePic(void)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion, const AMOV_GIMBAL_VELOCITY_T &speed, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::attitudeCorrection(const AMOV_GIMBAL_POS_T &pos, const AMOV_GIMBAL_VELOCITY_T &seppd, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t amovGimbal::IamovGimbalBase::extensionFuntions(void *cmd)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* The function creates a new gimbal object, which is a pointer to a new amovGimbal object, which is a
|
|
||||||
* pointer to a new Gimbal object, which is a pointer to a new IOStreamBase object
|
|
||||||
*
|
|
||||||
* @param type the type of the device, which is the same as the name of the class
|
|
||||||
* @param _IO The IOStreamBase object that is used to communicate with the device.
|
|
||||||
* @param _self the node ID of the device
|
|
||||||
* @param _remote the node ID of the remote device
|
|
||||||
*/
|
|
||||||
amovGimbal::gimbal::gimbal(const std::string &type, IOStreamBase *_IO,
|
|
||||||
uint32_t _self, uint32_t _remote)
|
|
||||||
{
|
|
||||||
typeName = type;
|
|
||||||
IO = _IO;
|
|
||||||
|
|
||||||
dev = amovGimbalCreator::createAmovGimbal(typeName, IO);
|
|
||||||
|
|
||||||
dev->nodeSet(_self, _remote);
|
|
||||||
}
|
|
||||||
|
|
||||||
amovGimbal::gimbal::~gimbal()
|
|
||||||
{
|
|
||||||
// 先干掉请求线程
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
|
||||||
delete dev;
|
|
||||||
}
|
|
||||||
@@ -1,101 +0,0 @@
|
|||||||
/*
|
|
||||||
* @Description: External interface of amov gimbals
|
|
||||||
* @Author: L LC @amov
|
|
||||||
* @Date: 2022-10-27 18:34:26
|
|
||||||
* @LastEditors: L LC @amov
|
|
||||||
* @LastEditTime: 2023-08-16 22:21:28
|
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/amov_gimbal.h
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef AMOV_GIMBAL_H
|
|
||||||
#define AMOV_GIMBAL_H
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <iostream>
|
|
||||||
|
|
||||||
#include "amov_gimbal_struct.h"
|
|
||||||
|
|
||||||
#define MAX_QUEUE_SIZE 100
|
|
||||||
namespace amovGimbal
|
|
||||||
{
|
|
||||||
#define IN
|
|
||||||
#define OUT
|
|
||||||
#define SET
|
|
||||||
|
|
||||||
static inline void idleCallback(double &frameAngleRoll, double &frameAnglePitch, double &frameAngleYaw,
|
|
||||||
double &imuAngleRoll, double &imuAnglePitch, double &imuAngleYaw,
|
|
||||||
double &fovX, double &fovY)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
static inline void idleMsgCallback(void *)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// Control data input and output
|
|
||||||
class IOStreamBase
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
IOStreamBase() {}
|
|
||||||
virtual ~IOStreamBase() {}
|
|
||||||
|
|
||||||
virtual bool open() = 0;
|
|
||||||
virtual bool close() = 0;
|
|
||||||
virtual bool isOpen() = 0;
|
|
||||||
virtual bool isBusy() = 0;
|
|
||||||
// These two functions need to be thread-safe
|
|
||||||
virtual bool inPutByte(IN uint8_t *byte) = 0;
|
|
||||||
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght) = 0;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Device interface
|
|
||||||
class IamovGimbalBase
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
IamovGimbalBase() {}
|
|
||||||
virtual ~IamovGimbalBase() {}
|
|
||||||
// functions
|
|
||||||
virtual void nodeSet(SET uint32_t _self, SET uint32_t _remote);
|
|
||||||
virtual uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
|
||||||
virtual uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
|
||||||
virtual uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
|
||||||
virtual uint32_t setGimabalHome(void);
|
|
||||||
virtual uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
|
||||||
virtual uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
|
||||||
virtual uint32_t setGimbalROI(const AMOV_GIMBAL_ROI_T area);
|
|
||||||
virtual uint32_t takePic(void);
|
|
||||||
virtual uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
|
||||||
virtual uint32_t attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion, const AMOV_GIMBAL_VELOCITY_T &speed, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
|
||||||
virtual uint32_t attitudeCorrection(const AMOV_GIMBAL_POS_T &pos, const AMOV_GIMBAL_VELOCITY_T &seppd, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
|
||||||
virtual uint32_t extensionFuntions(void *cmd);
|
|
||||||
};
|
|
||||||
|
|
||||||
class gimbal
|
|
||||||
{
|
|
||||||
private:
|
|
||||||
std::string typeName;
|
|
||||||
IOStreamBase *IO;
|
|
||||||
|
|
||||||
public:
|
|
||||||
// Instantiated device handle
|
|
||||||
IamovGimbalBase *dev;
|
|
||||||
|
|
||||||
// Protocol stack function items
|
|
||||||
void startStack(void);
|
|
||||||
void parserAuto(pStateInvoke callback = idleCallback);
|
|
||||||
void setParserCallback(pStateInvoke callback);
|
|
||||||
void setMsgCallback(pMsgInvoke callback);
|
|
||||||
|
|
||||||
AMOV_GIMBAL_STATE_T getGimabalState(void);
|
|
||||||
|
|
||||||
std::string name()
|
|
||||||
{
|
|
||||||
return typeName;
|
|
||||||
}
|
|
||||||
gimbal(const std::string &type, IOStreamBase *_IO,
|
|
||||||
uint32_t _self = 0x02, uint32_t _remote = 0X80);
|
|
||||||
~gimbal();
|
|
||||||
};
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
90
gimbal_ctrl/driver/src/amov_gimbal_factory.cpp
Normal file
90
gimbal_ctrl/driver/src/amov_gimbal_factory.cpp
Normal file
@@ -0,0 +1,90 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-24 15:48:47
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 16:27:10
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_factory.cpp
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "amov_gimbal_private.h"
|
||||||
|
#include "g1_gimbal_driver.h"
|
||||||
|
#include "Q10f_gimbal_driver.h"
|
||||||
|
#include "AT10_gimbal_driver.h"
|
||||||
|
#include "GX40_gimbal_driver.h"
|
||||||
|
|
||||||
|
#include <map>
|
||||||
|
#include <iterator>
|
||||||
|
|
||||||
|
namespace amovGimbalFactory
|
||||||
|
{
|
||||||
|
typedef amovGimbal::amovGimbalBase *(*createCallback)(amovGimbal::IOStreamBase *_IO);
|
||||||
|
typedef std::map<std::string, createCallback> callbackMap;
|
||||||
|
|
||||||
|
callbackMap amovGimbals =
|
||||||
|
{
|
||||||
|
{"G1", g1GimbalDriver::creat},
|
||||||
|
{"Q10f", Q10fGimbalDriver::creat},
|
||||||
|
{"AT10", AT10GimbalDriver::creat},
|
||||||
|
{"GX40", GX40GimbalDriver::creat}};
|
||||||
|
|
||||||
|
/* The amovGimbalCreator class is a factory class that creates an instance of the amovGimbal class */
|
||||||
|
// Factory used to create the gimbal instance
|
||||||
|
class amovGimbalCreator
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static amovGimbal::amovGimbalBase *createAmovGimbal(const std::string &type, amovGimbal::IOStreamBase *_IO)
|
||||||
|
{
|
||||||
|
callbackMap::iterator temp = amovGimbals.find(type);
|
||||||
|
|
||||||
|
if (temp != amovGimbals.end())
|
||||||
|
{
|
||||||
|
return (temp->second)(_IO);
|
||||||
|
}
|
||||||
|
std::cout << type << " is Unsupported device type!" << std::endl;
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
amovGimbalCreator()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
static amovGimbalCreator *pInstance;
|
||||||
|
static amovGimbalCreator *getInstance()
|
||||||
|
{
|
||||||
|
if (pInstance == NULL)
|
||||||
|
{
|
||||||
|
pInstance = new amovGimbalCreator();
|
||||||
|
}
|
||||||
|
return pInstance;
|
||||||
|
}
|
||||||
|
|
||||||
|
~amovGimbalCreator();
|
||||||
|
};
|
||||||
|
} // namespace amovGimbalFactory
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function creates a new gimbal object, which is a pointer to a new amovGimbal object, which is a
|
||||||
|
* pointer to a new Gimbal object, which is a pointer to a new IOStreamBase object
|
||||||
|
*
|
||||||
|
* @param type the type of the device, which is the same as the name of the class
|
||||||
|
* @param _IO The IOStreamBase object that is used to communicate with the device.
|
||||||
|
* @param _self the node ID of the device
|
||||||
|
* @param _remote the node ID of the remote device
|
||||||
|
*/
|
||||||
|
amovGimbal::gimbal::gimbal(const std::string &type, IOStreamBase *_IO,
|
||||||
|
uint32_t _self, uint32_t _remote)
|
||||||
|
{
|
||||||
|
typeName = type;
|
||||||
|
|
||||||
|
devHandle = amovGimbalFactory::amovGimbalCreator::createAmovGimbal(typeName, _IO);
|
||||||
|
|
||||||
|
((amovGimbalBase *)(devHandle))->nodeSet(_self, _remote);
|
||||||
|
}
|
||||||
|
|
||||||
|
amovGimbal::gimbal::~gimbal()
|
||||||
|
{
|
||||||
|
// 先干掉请求线程
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
||||||
|
delete ((amovGimbalBase *)(devHandle));
|
||||||
|
}
|
||||||
229
gimbal_ctrl/driver/src/amov_gimbal_interface.cpp
Normal file
229
gimbal_ctrl/driver/src/amov_gimbal_interface.cpp
Normal file
@@ -0,0 +1,229 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-24 16:00:28
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 17:18:34
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_interface.cpp
|
||||||
|
*/
|
||||||
|
#include "amov_gimbal_private.h"
|
||||||
|
|
||||||
|
// must realize
|
||||||
|
void amovGimbal::gimbal::startStack(void)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)(this->devHandle))->stackStart();
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::parserAuto(pAmovGimbalStateInvoke callback, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)(this->devHandle))->parserStart(callback, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::setParserCallback(pAmovGimbalStateInvoke callback, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)(this->devHandle))->updateGimbalStateCallback = callback;
|
||||||
|
((amovGimbalBase *)(this->devHandle))->updataCaller = caller;
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::setMsgCallback(pAmovGimbalMsgInvoke callback, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)(this->devHandle))->msgCustomCallback = callback;
|
||||||
|
((amovGimbalBase *)(this->devHandle))->msgCaller = caller;
|
||||||
|
}
|
||||||
|
|
||||||
|
AMOV_GIMBAL_STATE_T amovGimbal::gimbal::getGimabalState(void)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)(this->devHandle))->mState.lock();
|
||||||
|
AMOV_GIMBAL_STATE_T temp = ((amovGimbalBase *)(this->devHandle))->state;
|
||||||
|
((amovGimbalBase *)(this->devHandle))->mState.unlock();
|
||||||
|
return temp;
|
||||||
|
}
|
||||||
|
|
||||||
|
// gimbal funtions maybe realize
|
||||||
|
uint32_t amovGimbal::gimbal::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimabalPos(pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimabalPos(const AMOV_GIMBAL_POS_T &pos)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimabalSpeed(speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimabalFollowSpeed(followSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimabalHome(void)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimabalHome();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimabalHome(void)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimbalZoom(zoom, targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimbalFocus(zoom, targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGimbalROI(const AMOV_GIMBAL_ROI_T area)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimbalROI(area);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGimbalROI(const AMOV_GIMBAL_ROI_T area)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::takePic(void)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->takePic();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::takePic(void)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setVideo(newState);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setVideo(const AMOV_GIMBAL_VIDEO_T newState)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->attitudeCorrection(quaterion, speed, acc, extenData);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->attitudeCorrection(pos, speed, acc, extenData);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::attitudeCorrection(const AMOV_GIMBAL_POS_T &pos,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &speed,
|
||||||
|
const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGNSSInfo(lng, lat, alt, nState, relAlt);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::gimbal::extensionFuntions(void *cmd)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->extensionFuntions(cmd);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbal::IamovGimbalBase::extensionFuntions(void *cmd)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::gimbal::setGimbalPosBlock(const AMOV_GIMBAL_POS_T &pos)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimbalPosBlock(pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::IamovGimbalBase::setGimbalPosBlock(const AMOV_GIMBAL_POS_T &pos)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::gimbal::setGimabalHomeBlock(void)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimabalHomeBlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::IamovGimbalBase::setGimabalHomeBlock(void)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::gimbal::setGimbalZoomBlock(float targetRate)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->setGimbalZoomBlock(targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::IamovGimbalBase::setGimbalZoomBlock(float targetRate)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::gimbal::takePicBlock(void)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->takePicBlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::IamovGimbalBase::takePicBlock(void)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::gimbal::calibrationBlock(void)
|
||||||
|
{
|
||||||
|
return ((amovGimbalBase *)(this->devHandle))->calibrationBlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbal::IamovGimbalBase::calibrationBlock(void)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
152
gimbal_ctrl/driver/src/amov_gimbal_interface_c.cpp
Normal file
152
gimbal_ctrl/driver/src/amov_gimbal_interface_c.cpp
Normal file
@@ -0,0 +1,152 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-27 12:28:32
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-06 11:36:30
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_interface_c.cpp
|
||||||
|
*/
|
||||||
|
#include "amov_gimbal_private.h"
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
void amovGimbalSetRcvBytes(pAmovGimbalInputBytesInvoke callbaclk, void *handle, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::gimbal *)handle)->setRcvBytes(callbaclk, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalSetSendBytes(pAmovGimbalOutputBytesInvoke callbaclk, void *handle, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::gimbal *)handle)->setSendBytes(callbaclk, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalInBytesCallback(uint8_t *pData, uint32_t len, void *handle)
|
||||||
|
{
|
||||||
|
amovGimbal::gimbal::inBytesCallback(pData, len, (amovGimbal::gimbal *)handle);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalCreat(char *type, uint32_t selfId, uint32_t gimbalId, void *handle)
|
||||||
|
{
|
||||||
|
std::string strType = type;
|
||||||
|
handle = new amovGimbal::gimbal(strType, nullptr, selfId, gimbalId);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalStart(pAmovGimbalStateInvoke callback, void *handle, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::gimbal *)handle)->startStack();
|
||||||
|
((amovGimbal::gimbal *)handle)->parserAuto(callback, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalChangeStateCallback(pAmovGimbalStateInvoke callback, void *handle, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::gimbal *)handle)->setParserCallback(callback, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbalSetMsgCallback(pAmovGimbalMsgInvoke callback, void *handle, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::gimbal *)handle)->setMsgCallback(callback, caller);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimabalPos(AMOV_GIMBAL_POS_T *pos, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimabalPos(*pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimabalSpeed(AMOV_GIMBAL_POS_T *speed, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimabalSpeed(*speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimabalFollowSpeed(AMOV_GIMBAL_POS_T *followSpeed, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimabalFollowSpeed(*followSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimabalHome(void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimabalHome();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimbalZoom(zoom, targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimbalFocus(zoom, targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGimbalROI(AMOV_GIMBAL_ROI_T *area, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimbalROI(*area);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalTakePic(void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->takePic();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetVideo(AMOV_GIMBAL_VIDEO_T newState, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setVideo(newState);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalAttitudeCorrectionQ(AMOV_GIMBAL_QUATERNION_T *quaterion,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *speed,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *acc, void *extenData, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->attitudeCorrection(*quaterion, *speed, *acc, extenData);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalAttitudeCorrectionE(AMOV_GIMBAL_POS_T *pos,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *speed,
|
||||||
|
AMOV_GIMBAL_VELOCITY_T *acc, void *extenData, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->attitudeCorrection(*pos, *speed, *acc, extenData);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalSetGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGNSSInfo(lng, lat, alt, nState, relAlt);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t amovGimbalExtensionFuntions(void *cmd, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->extensionFuntions(cmd);
|
||||||
|
}
|
||||||
|
|
||||||
|
void getGimabalState(AMOV_GIMBAL_STATE_T *state, void *handle)
|
||||||
|
{
|
||||||
|
*state = ((amovGimbal::gimbal *)handle)->getGimabalState();
|
||||||
|
}
|
||||||
|
|
||||||
|
void getGimbalType(char *type, void *handle)
|
||||||
|
{
|
||||||
|
std::string temp = ((amovGimbal::gimbal *)handle)->name();
|
||||||
|
temp.copy(type, temp.size(), 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbalSetGimbalPosBlock(AMOV_GIMBAL_POS_T *pos, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimbalPosBlock(*pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbalSetGimabalHomeBlock(void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimabalHomeBlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbalSetGimbalZoomBlock(float targetRate, void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->setGimbalZoomBlock(targetRate);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbalTakePicBlock(void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->takePicBlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool amovGimbalCalibrationBlock(void *handle)
|
||||||
|
{
|
||||||
|
return ((amovGimbal::gimbal *)handle)->calibrationBlock();
|
||||||
|
}
|
||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author : Aiyangsky
|
* @Author : Aiyangsky
|
||||||
* @Date : 2023-05-13 10:39:20
|
* @Date : 2023-05-13 10:39:20
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-08-16 22:30:53
|
* @LastEditTime: 2023-12-05 17:18:06
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/amov_gimbal_private.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_private.h
|
||||||
*/
|
*/
|
||||||
#ifndef __AMOV_GIMABL_PRIVATE_H
|
#ifndef __AMOV_GIMABL_PRIVATE_H
|
||||||
#define __AMOV_GIMABL_PRIVATE_H
|
#define __AMOV_GIMABL_PRIVATE_H
|
||||||
@@ -12,12 +12,12 @@
|
|||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#include <thread>
|
#include <thread>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <mutex>
|
#include <mutex>
|
||||||
|
|
||||||
#include "amov_gimbal.h"
|
#include "amovGimbal/amov_gimbal.h"
|
||||||
|
#include "amovGimbal/amov_gimbal_c.h"
|
||||||
|
|
||||||
#include "Ring_Fifo.h"
|
#include "Ring_Fifo.h"
|
||||||
#include "amov_tool.h"
|
#include "amov_tool.h"
|
||||||
@@ -28,14 +28,28 @@ namespace amovGimbal
|
|||||||
public:
|
public:
|
||||||
AMOV_GIMBAL_STATE_T state;
|
AMOV_GIMBAL_STATE_T state;
|
||||||
std::mutex mState;
|
std::mutex mState;
|
||||||
IOStreamBase *IO;
|
|
||||||
pStateInvoke updateGimbalStateCallback;
|
// IO类
|
||||||
pMsgInvoke msgCustomCallback = idleMsgCallback;
|
IOStreamBase *IO = nullptr;
|
||||||
|
// 适用于C的函数指针
|
||||||
|
void *inBytesCaller = nullptr;
|
||||||
|
pAmovGimbalInputBytesInvoke inBytes = nullptr;
|
||||||
|
void *outBytesCaller = nullptr;
|
||||||
|
pAmovGimbalOutputBytesInvoke outBytes = nullptr;
|
||||||
|
|
||||||
|
void *updataCaller = nullptr;
|
||||||
|
pAmovGimbalStateInvoke updateGimbalStateCallback;
|
||||||
|
void *msgCaller = nullptr;
|
||||||
|
pAmovGimbalMsgInvoke msgCustomCallback = idleMsgCallback;
|
||||||
|
|
||||||
fifoRing *rxQueue;
|
fifoRing *rxQueue;
|
||||||
fifoRing *txQueue;
|
fifoRing *txQueue;
|
||||||
|
|
||||||
PamovGimbalBase(SET IOStreamBase *_IO)
|
std::thread::native_handle_type parserThreadHanle = 0;
|
||||||
|
std::thread::native_handle_type sendThreadHanle = 0;
|
||||||
|
std::thread::native_handle_type stackThreadHanle = 0;
|
||||||
|
|
||||||
|
PamovGimbalBase(IOStreamBase *_IO)
|
||||||
{
|
{
|
||||||
IO = _IO;
|
IO = _IO;
|
||||||
}
|
}
|
||||||
@@ -49,9 +63,45 @@ namespace amovGimbal
|
|||||||
{
|
{
|
||||||
delete rxQueue;
|
delete rxQueue;
|
||||||
}
|
}
|
||||||
|
// set thread kill anytime
|
||||||
|
pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
|
||||||
|
parserThreadHanle = parserThreadHanle == 0 ? 0 : pthread_cancel(parserThreadHanle);
|
||||||
|
sendThreadHanle = sendThreadHanle == 0 ? 0 : pthread_cancel(sendThreadHanle);
|
||||||
|
stackThreadHanle = stackThreadHanle == 0 ? 0 : pthread_cancel(stackThreadHanle);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Device interface
|
||||||
|
class IamovGimbalBase
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
IamovGimbalBase() {}
|
||||||
|
virtual ~IamovGimbalBase() {}
|
||||||
|
|
||||||
|
// non-block functions
|
||||||
|
virtual uint32_t setGimabalPos(const AMOV_GIMBAL_POS_T &pos);
|
||||||
|
virtual uint32_t setGimabalSpeed(const AMOV_GIMBAL_POS_T &speed);
|
||||||
|
virtual uint32_t setGimabalFollowSpeed(const AMOV_GIMBAL_POS_T &followSpeed);
|
||||||
|
|
||||||
|
virtual uint32_t setGimabalHome(void);
|
||||||
|
virtual uint32_t setGimbalZoom(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
virtual uint32_t setGimbalFocus(AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0);
|
||||||
|
virtual uint32_t setGimbalROI(const AMOV_GIMBAL_ROI_T area);
|
||||||
|
virtual uint32_t takePic(void);
|
||||||
|
virtual uint32_t setVideo(const AMOV_GIMBAL_VIDEO_T newState);
|
||||||
|
virtual uint32_t attitudeCorrection(const AMOV_GIMBAL_QUATERNION_T &quaterion, const AMOV_GIMBAL_VELOCITY_T &speed, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
||||||
|
virtual uint32_t attitudeCorrection(const AMOV_GIMBAL_POS_T &pos, const AMOV_GIMBAL_VELOCITY_T &seppd, const AMOV_GIMBAL_VELOCITY_T &acc, void *extenData);
|
||||||
|
virtual uint32_t setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt);
|
||||||
|
virtual uint32_t extensionFuntions(void *cmd);
|
||||||
|
|
||||||
|
// block functions
|
||||||
|
virtual bool setGimbalPosBlock(const AMOV_GIMBAL_POS_T &pos);
|
||||||
|
virtual bool setGimabalHomeBlock(void);
|
||||||
|
virtual bool setGimbalZoomBlock(float targetRate);
|
||||||
|
virtual bool takePicBlock(void);
|
||||||
|
virtual bool calibrationBlock(void);
|
||||||
|
};
|
||||||
|
|
||||||
class amovGimbalBase : public IamovGimbalBase, public PamovGimbalBase
|
class amovGimbalBase : public IamovGimbalBase, public PamovGimbalBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -68,7 +118,9 @@ namespace amovGimbal
|
|||||||
virtual void mainLoop(void);
|
virtual void mainLoop(void);
|
||||||
|
|
||||||
virtual void stackStart(void);
|
virtual void stackStart(void);
|
||||||
virtual void parserStart(amovGimbal::pStateInvoke callback);
|
virtual void parserStart(pAmovGimbalStateInvoke callback, void *caller);
|
||||||
|
|
||||||
|
virtual void nodeSet(SET uint32_t _self, SET uint32_t _remote);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
amovGimbalBase(IOStreamBase *_IO);
|
amovGimbalBase(IOStreamBase *_IO);
|
||||||
|
|||||||
197
gimbal_ctrl/driver/src/amov_gimbal_realize.cpp
Normal file
197
gimbal_ctrl/driver/src/amov_gimbal_realize.cpp
Normal file
@@ -0,0 +1,197 @@
|
|||||||
|
/*
|
||||||
|
* @Description:
|
||||||
|
* @Author: L LC @amov
|
||||||
|
* @Date: 2023-11-24 15:55:37
|
||||||
|
* @LastEditors: L LC @amov
|
||||||
|
* @LastEditTime: 2023-12-05 17:19:19
|
||||||
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_realize.cpp
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "amov_gimbal_private.h"
|
||||||
|
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
#define MAX_PACK_SIZE 280
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This is a constructor for the amovGimbalBase class that initializes its parent classes with an
|
||||||
|
* IOStreamBase object.
|
||||||
|
*
|
||||||
|
* @param _IO _IO is a pointer to an object of type amovGimbal::IOStreamBase, which is the base class
|
||||||
|
* for input/output streams used by the amovGimbal class. This parameter is passed to the constructor
|
||||||
|
* of amovGimbalBase, which is a derived class of I
|
||||||
|
*/
|
||||||
|
amovGimbal::amovGimbalBase::amovGimbalBase(amovGimbal::IOStreamBase *_IO) : amovGimbal::IamovGimbalBase(), amovGimbal::PamovGimbalBase(_IO)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function is a destructor that sleeps for 50 milliseconds and closes an IO object.
|
||||||
|
*/
|
||||||
|
amovGimbal::amovGimbalBase::~amovGimbalBase()
|
||||||
|
{
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
||||||
|
IO->close();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This function retrieves a packet from a ring buffer queue and returns a boolean value indicating
|
||||||
|
* whether the operation was successful or not.
|
||||||
|
*
|
||||||
|
* @param void void is a keyword in C++ that represents the absence of a type. In this function, it is
|
||||||
|
* used to indicate that the function does not return any value.
|
||||||
|
*
|
||||||
|
* @return a boolean value, which indicates whether or not a data packet was successfully retrieved
|
||||||
|
* from a ring buffer queue.
|
||||||
|
*/
|
||||||
|
bool amovGimbal::amovGimbalBase::getRxPack(OUT void *pack)
|
||||||
|
{
|
||||||
|
bool state = false;
|
||||||
|
state = rxQueue->outCell(pack);
|
||||||
|
return state;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This function sends data from a buffer to an output device if it is not busy and open.
|
||||||
|
*/
|
||||||
|
void amovGimbal::amovGimbalBase::send(void)
|
||||||
|
{
|
||||||
|
uint8_t tempBuffer[MAX_PACK_SIZE];
|
||||||
|
|
||||||
|
if (IO == nullptr)
|
||||||
|
{
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
if (txQueue->outCell(&tempBuffer))
|
||||||
|
{
|
||||||
|
this->outBytes((uint8_t *)&tempBuffer, calPackLen(tempBuffer), outBytesCaller);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
if (!IO->isBusy() && IO->isOpen())
|
||||||
|
{
|
||||||
|
if (txQueue->outCell(&tempBuffer))
|
||||||
|
{
|
||||||
|
IO->outPutBytes((uint8_t *)&tempBuffer, calPackLen(tempBuffer));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* "If the input byte is available, then parse it."
|
||||||
|
*
|
||||||
|
* The function is a loop that runs forever. It calls the IO->inPutByte() function to get a byte from
|
||||||
|
* the serial port. If the byte is available, then it calls the parser() function to parse the byte
|
||||||
|
*/
|
||||||
|
void amovGimbal::amovGimbalBase::parserLoop(void)
|
||||||
|
{
|
||||||
|
uint8_t temp[65536];
|
||||||
|
uint32_t i = 0, getCount = 0;
|
||||||
|
if (IO == nullptr)
|
||||||
|
{
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
getCount = inBytes(temp, inBytesCaller);
|
||||||
|
|
||||||
|
for (i = 0; i < getCount; i++)
|
||||||
|
{
|
||||||
|
parser(temp[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
getCount = IO->inPutBytes(temp);
|
||||||
|
|
||||||
|
for (i = 0; i < getCount; i++)
|
||||||
|
{
|
||||||
|
parser(temp[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::amovGimbalBase::sendLoop(void)
|
||||||
|
{
|
||||||
|
send();
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::amovGimbalBase::mainLoop(void)
|
||||||
|
{
|
||||||
|
uint8_t tempBuffer[MAX_PACK_SIZE];
|
||||||
|
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
if (getRxPack(tempBuffer))
|
||||||
|
{
|
||||||
|
msgCustomCallback(tempBuffer, msgCaller);
|
||||||
|
convert(tempBuffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::amovGimbalBase::stackStart(void)
|
||||||
|
{
|
||||||
|
if (!this->IO->isOpen() && this->IO != nullptr)
|
||||||
|
{
|
||||||
|
this->IO->open();
|
||||||
|
}
|
||||||
|
|
||||||
|
// 当且仅当需要库主动查询时才启用解析器线程
|
||||||
|
if (inBytes != nullptr || this->IO != nullptr)
|
||||||
|
{
|
||||||
|
std::thread parserLoop(&amovGimbalBase::parserLoop, this);
|
||||||
|
this->parserThreadHanle = parserLoop.native_handle();
|
||||||
|
parserLoop.detach();
|
||||||
|
}
|
||||||
|
|
||||||
|
std::thread sendLoop(&amovGimbalBase::sendLoop, this);
|
||||||
|
this->sendThreadHanle = sendLoop.native_handle();
|
||||||
|
sendLoop.detach();
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::amovGimbalBase::parserStart(pAmovGimbalStateInvoke callback, void *caller)
|
||||||
|
{
|
||||||
|
this->updateGimbalStateCallback = callback;
|
||||||
|
this->updataCaller = caller;
|
||||||
|
|
||||||
|
std::thread mainLoop(&amovGimbalBase::mainLoop, this);
|
||||||
|
|
||||||
|
this->stackThreadHanle = mainLoop.native_handle();
|
||||||
|
|
||||||
|
mainLoop.detach();
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::amovGimbalBase::nodeSet(SET uint32_t _self, SET uint32_t _remote)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::setRcvBytes(pAmovGimbalInputBytesInvoke callbaclk, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::amovGimbalBase *)(this->devHandle))->inBytes = callbaclk;
|
||||||
|
((amovGimbal::amovGimbalBase *)(this->devHandle))->inBytesCaller = caller;
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::setSendBytes(pAmovGimbalOutputBytesInvoke callbaclk, void *caller)
|
||||||
|
{
|
||||||
|
((amovGimbal::amovGimbalBase *)(this->devHandle))->outBytes = callbaclk;
|
||||||
|
((amovGimbal::amovGimbalBase *)(this->devHandle))->outBytesCaller = caller;
|
||||||
|
}
|
||||||
|
|
||||||
|
void amovGimbal::gimbal::inBytesCallback(uint8_t *pData, uint32_t len, gimbal *handle)
|
||||||
|
{
|
||||||
|
uint32_t i = 0;
|
||||||
|
for (i = 0; i < len; i++)
|
||||||
|
{
|
||||||
|
((amovGimbalBase *)((handle)->devHandle))->parser(pData[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,89 +0,0 @@
|
|||||||
/*
|
|
||||||
* @Description: Common Data Structures of gimbal
|
|
||||||
* @Author: L LC @amov
|
|
||||||
* @Date: 2022-10-31 11:56:43
|
|
||||||
* @LastEditors: L LC @amov
|
|
||||||
* @LastEditTime: 2023-08-16 22:21:46
|
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/amov_gimbal_struct.h
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#ifndef __AMOV_GIMABL_STRUCT_H
|
|
||||||
#define __AMOV_GIMABL_STRUCT_H
|
|
||||||
|
|
||||||
namespace amovGimbal
|
|
||||||
{
|
|
||||||
typedef void (*pStateInvoke)(double &frameAngleRoll, double &frameAnglePitch, double &frameAngleYaw,
|
|
||||||
double &imuAngleRoll, double &imuAnglePitch, double &imuAngleYaw,
|
|
||||||
double &fovX, double &fovY);
|
|
||||||
typedef void (*pMsgInvoke)(void *msg);
|
|
||||||
|
|
||||||
typedef enum
|
|
||||||
{
|
|
||||||
AMOV_GIMBAL_MODE_LOCK,
|
|
||||||
AMOV_GIMBAL_MODE_NULOCK,
|
|
||||||
} AMOV_GIMBAL_MODE_T;
|
|
||||||
|
|
||||||
typedef enum
|
|
||||||
{
|
|
||||||
AMOV_GIMBAL_VIDEO_TAKE,
|
|
||||||
AMOV_GIMBAL_VIDEO_OFF
|
|
||||||
} AMOV_GIMBAL_VIDEO_T;
|
|
||||||
|
|
||||||
typedef enum
|
|
||||||
{
|
|
||||||
AMOV_GIMBAL_ZOOM_IN,
|
|
||||||
AMOV_GIMBAL_ZOOM_OUT,
|
|
||||||
AMOV_GIMBAL_ZOOM_STOP
|
|
||||||
} AMOV_GIMBAL_ZOOM_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
double yaw;
|
|
||||||
double roll;
|
|
||||||
double pitch;
|
|
||||||
} AMOV_GIMBAL_POS_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
double x;
|
|
||||||
double y;
|
|
||||||
} AMOV_GIMBAL_FOV_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
AMOV_GIMBAL_MODE_T workMode;
|
|
||||||
AMOV_GIMBAL_VIDEO_T video;
|
|
||||||
AMOV_GIMBAL_POS_T abs;
|
|
||||||
AMOV_GIMBAL_POS_T rel;
|
|
||||||
AMOV_GIMBAL_POS_T maxFollow;
|
|
||||||
AMOV_GIMBAL_FOV_T fov;
|
|
||||||
} AMOV_GIMBAL_STATE_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
uint32_t centreX;
|
|
||||||
uint32_t centreY;
|
|
||||||
uint32_t hight;
|
|
||||||
uint32_t width;
|
|
||||||
} AMOV_GIMBAL_ROI_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
double q0;
|
|
||||||
double q1;
|
|
||||||
double q2;
|
|
||||||
double q3;
|
|
||||||
} AMOV_GIMBAL_QUATERNION_T;
|
|
||||||
|
|
||||||
typedef struct
|
|
||||||
{
|
|
||||||
double x;
|
|
||||||
double y;
|
|
||||||
double z;
|
|
||||||
} AMOV_GIMBAL_VELOCITY_T;
|
|
||||||
|
|
||||||
} // namespace amovGimbal
|
|
||||||
|
|
||||||
#endif
|
|
||||||
@@ -3,10 +3,12 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-07-31 18:30:33
|
* @Date: 2023-07-31 18:30:33
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-07-31 18:55:18
|
* @LastEditTime: 2023-12-05 16:26:05
|
||||||
* @FilePath: /gimbal-sdk-multi-platform/src/amov_tool.h
|
* @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_tool.h
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#ifndef __AMOVGIMABL_TOOL_H
|
||||||
|
#define __AMOVGIMABL_TOOL_H
|
||||||
namespace amovGimbalTools
|
namespace amovGimbalTools
|
||||||
{
|
{
|
||||||
static inline unsigned short conversionBigLittle(unsigned short value)
|
static inline unsigned short conversionBigLittle(unsigned short value)
|
||||||
@@ -27,3 +29,4 @@ namespace amovGimbalTools
|
|||||||
return temp;
|
return temp;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|||||||
@@ -3,11 +3,10 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-04-12 09:12:52
|
* @Date: 2023-04-12 09:12:52
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-04-18 11:37:42
|
* @LastEditTime: 2023-12-05 17:33:29
|
||||||
* @FilePath: /spirecv-gimbal-sdk/gimbal_ctrl/sv_gimbal.cpp
|
* @FilePath: /SpireCV/gimbal_ctrl/sv_gimbal.cpp
|
||||||
*/
|
*/
|
||||||
#include "amov_gimbal.h"
|
#include "amovGimbal/amov_gimbal.h"
|
||||||
#include "amov_gimbal_struct.h"
|
|
||||||
|
|
||||||
#include "sv_gimbal.h"
|
#include "sv_gimbal.h"
|
||||||
#include "sv_gimbal_io.hpp"
|
#include "sv_gimbal_io.hpp"
|
||||||
@@ -20,18 +19,42 @@ namespace sv
|
|||||||
std::map<std::string, void *> Gimbal::IOList;
|
std::map<std::string, void *> Gimbal::IOList;
|
||||||
std::mutex Gimbal::IOListMutex;
|
std::mutex Gimbal::IOListMutex;
|
||||||
|
|
||||||
std::map<GimbalType, std::string> gimbaltypeList =
|
typedef struct
|
||||||
{
|
|
||||||
{GimbalType::G1, "G1"},
|
|
||||||
{GimbalType::Q10f, "Q10f"},
|
|
||||||
{GimbalType::AT10, "AT10"}};
|
|
||||||
|
|
||||||
std::string &cvGimbalType2Str(const GimbalType &type)
|
|
||||||
{
|
{
|
||||||
std::map<GimbalType, std::string>::iterator temp = gimbaltypeList.find(type);
|
std::string name;
|
||||||
|
GimbalLink supportLink;
|
||||||
|
} gimbalTrait;
|
||||||
|
|
||||||
|
std::map<GimbalType, gimbalTrait> gimbaltypeList =
|
||||||
|
{
|
||||||
|
{GimbalType::G1, {"G1", GimbalLink::SERIAL}},
|
||||||
|
{GimbalType::Q10f, {"Q10f", GimbalLink::SERIAL}},
|
||||||
|
{GimbalType::AT10, {"AT10", GimbalLink::SERIAL | GimbalLink::ETHERNET_TCP}},
|
||||||
|
{GimbalType::GX40, {"GX40", GimbalLink::SERIAL | GimbalLink::ETHERNET_TCP | GimbalLink::ETHERNET_UDP}}};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function `svGimbalType2Str` converts a `GimbalType` enum value to its corresponding string
|
||||||
|
* representation.
|
||||||
|
*
|
||||||
|
* @return a reference to a string.
|
||||||
|
*/
|
||||||
|
std::string &svGimbalType2Str(const GimbalType &type)
|
||||||
|
{
|
||||||
|
std::map<GimbalType, gimbalTrait>::iterator temp = gimbaltypeList.find(type);
|
||||||
if (temp != gimbaltypeList.end())
|
if (temp != gimbaltypeList.end())
|
||||||
{
|
{
|
||||||
return (temp->second);
|
return (temp->second).name;
|
||||||
|
}
|
||||||
|
throw "Error: Unsupported gimbal device type!!!!";
|
||||||
|
exit(-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
GimbalLink &svGimbalTypeFindLinkType(const GimbalType &type)
|
||||||
|
{
|
||||||
|
std::map<GimbalType, gimbalTrait>::iterator temp = gimbaltypeList.find(type);
|
||||||
|
if (temp != gimbaltypeList.end())
|
||||||
|
{
|
||||||
|
return (temp->second).supportLink;
|
||||||
}
|
}
|
||||||
throw "Error: Unsupported gimbal device type!!!!";
|
throw "Error: Unsupported gimbal device type!!!!";
|
||||||
exit(-1);
|
exit(-1);
|
||||||
@@ -100,17 +123,29 @@ void sv::Gimbal::setNetIp(const std::string &ip)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This function sets the network port for a Gimbal object in C++.
|
* The function sets the TCP network port for the Gimbal object.
|
||||||
*
|
*
|
||||||
* @param port The "port" parameter is an integer value that represents the network port number that
|
* @param port The parameter "port" is an integer that represents the TCP network port number.
|
||||||
* the Gimbal object will use for communication. This function sets the value of the "m_net_port"
|
|
||||||
* member variable of the Gimbal object to the value passed in as the "port" parameter.
|
|
||||||
*/
|
*/
|
||||||
void sv::Gimbal::setNetPort(const int &port)
|
void sv::Gimbal::setTcpNetPort(const int &port)
|
||||||
{
|
{
|
||||||
this->m_net_port = port;
|
this->m_net_port = port;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function sets the UDP network ports for receiving and sending data.
|
||||||
|
*
|
||||||
|
* @param recvPort The recvPort parameter is the port number that the Gimbal object will use to receive
|
||||||
|
* UDP packets.
|
||||||
|
* @param sendPort The sendPort parameter is the port number used for sending data over UDP (User
|
||||||
|
* Datagram Protocol) network communication.
|
||||||
|
*/
|
||||||
|
void sv::Gimbal::setUdpNetPort(const int &recvPort, const int &sendPort)
|
||||||
|
{
|
||||||
|
this->m_net_recv_port = recvPort;
|
||||||
|
this->m_net_send_port = sendPort;
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The function sets a parser callback for a gimbal device.
|
* The function sets a parser callback for a gimbal device.
|
||||||
*
|
*
|
||||||
@@ -121,25 +156,31 @@ void sv::Gimbal::setNetPort(const int &port)
|
|||||||
void sv::Gimbal::setStateCallback(sv::PStateInvoke callback)
|
void sv::Gimbal::setStateCallback(sv::PStateInvoke callback)
|
||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
pdevTemp->setParserCallback(callback);
|
m_callback = callback;
|
||||||
|
pdevTemp->setParserCallback(sv::Gimbal::gimbalUpdataCallback, this);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The function `creatIO` creates an IO object for a gimbal device and adds it to a list of IO objects
|
* The function `sv::Gimbal::creatIO` creates an IO object based on the specified gimbal type and link
|
||||||
* if it doesn't already exist.
|
* type, and returns a pointer to the created object.
|
||||||
*
|
*
|
||||||
* @param dev A pointer to an instance of the `Gimbal` class.
|
* @param dev The "dev" parameter is a pointer to an object of type "sv::Gimbal". It is used to access
|
||||||
* @param IO The parameter "IO" is a pointer to an object that represents the input/output (IO) device
|
* the member variables of the Gimbal object, such as "m_serial_port", "m_serial_baud_rate",
|
||||||
* for the gimbal. It is used to establish a connection with the gimbal and perform communication
|
* "m_serial_timeout", etc. These variables store information about
|
||||||
* operations.
|
|
||||||
*
|
*
|
||||||
* @return a boolean value.
|
* @return a void pointer.
|
||||||
*/
|
*/
|
||||||
void *sv::Gimbal::creatIO(sv::Gimbal *dev)
|
void *sv::Gimbal::creatIO(sv::Gimbal *dev)
|
||||||
{
|
{
|
||||||
IOListMutex.lock();
|
IOListMutex.lock();
|
||||||
std::map<std::string, void *>::iterator list = IOList.find(dev->m_serial_port);
|
std::map<std::string, void *>::iterator list = IOList.find(dev->m_serial_port);
|
||||||
std::pair<std::string, void *> key("NULL", nullptr);
|
std::pair<std::string, void *> key("NULL", nullptr);
|
||||||
|
GimbalLink link = svGimbalTypeFindLinkType(dev->m_gimbal_type);
|
||||||
|
|
||||||
|
if ((dev->m_gimbal_link & svGimbalTypeFindLinkType(dev->m_gimbal_type)) == GimbalLink::NONE)
|
||||||
|
{
|
||||||
|
throw std::runtime_error("gimbal Unsupported linktype !!!");
|
||||||
|
}
|
||||||
|
|
||||||
if (list == IOList.end())
|
if (list == IOList.end())
|
||||||
{
|
{
|
||||||
@@ -159,20 +200,35 @@ void *sv::Gimbal::creatIO(sv::Gimbal *dev)
|
|||||||
}
|
}
|
||||||
else if (dev->m_gimbal_link == sv::GimbalLink::ETHERNET_TCP)
|
else if (dev->m_gimbal_link == sv::GimbalLink::ETHERNET_TCP)
|
||||||
{
|
{
|
||||||
|
TCPClient *tcp;
|
||||||
|
tcp = new TCPClient(dev->m_net_ip, dev->m_net_port);
|
||||||
|
key.first = dev->m_net_ip;
|
||||||
|
key.second = (void *)tcp;
|
||||||
|
IOList.insert(key);
|
||||||
}
|
}
|
||||||
else if (dev->m_gimbal_link == sv::GimbalLink::ETHERNET_UDP)
|
else if (dev->m_gimbal_link == sv::GimbalLink::ETHERNET_UDP)
|
||||||
{
|
{
|
||||||
|
UDP *udp;
|
||||||
|
udp = new UDP(dev->m_net_ip, dev->m_net_recv_port, dev->m_net_send_port);
|
||||||
|
key.first = dev->m_net_ip;
|
||||||
|
key.second = (void *)udp;
|
||||||
|
IOList.insert(key);
|
||||||
}
|
}
|
||||||
else
|
}
|
||||||
{
|
else
|
||||||
std::cout << "Error: gimbal IO has opened!!!" << std::endl;
|
{
|
||||||
}
|
std::cout << "Error: gimbal IO has opened!!!" << std::endl;
|
||||||
}
|
}
|
||||||
IOListMutex.unlock();
|
IOListMutex.unlock();
|
||||||
|
|
||||||
return key.second;
|
return key.second;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The function removes a Gimbal device from the IOList.
|
||||||
|
*
|
||||||
|
* @param dev dev is a pointer to an object of type sv::Gimbal.
|
||||||
|
*/
|
||||||
void sv::Gimbal::removeIO(sv::Gimbal *dev)
|
void sv::Gimbal::removeIO(sv::Gimbal *dev)
|
||||||
{
|
{
|
||||||
IOListMutex.lock();
|
IOListMutex.lock();
|
||||||
@@ -180,6 +236,7 @@ void sv::Gimbal::removeIO(sv::Gimbal *dev)
|
|||||||
|
|
||||||
IOListMutex.unlock();
|
IOListMutex.unlock();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The function opens a communication interface with a gimbal device and sets up a parser to handle
|
* The function opens a communication interface with a gimbal device and sets up a parser to handle
|
||||||
* incoming data.
|
* incoming data.
|
||||||
@@ -196,14 +253,16 @@ bool sv::Gimbal::open(PStateInvoke callback)
|
|||||||
bool ret = false;
|
bool ret = false;
|
||||||
|
|
||||||
this->IO = creatIO(this);
|
this->IO = creatIO(this);
|
||||||
|
|
||||||
if (this->IO != nullptr)
|
if (this->IO != nullptr)
|
||||||
{
|
{
|
||||||
std::string driverName;
|
std::string driverName;
|
||||||
driverName = sv::cvGimbalType2Str(this->m_gimbal_type);
|
driverName = sv::svGimbalType2Str(this->m_gimbal_type);
|
||||||
this->dev = new amovGimbal::gimbal(driverName, (amovGimbal::IOStreamBase *)this->IO);
|
this->dev = new amovGimbal::gimbal(driverName, (amovGimbal::IOStreamBase *)this->IO);
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
pdevTemp->startStack();
|
pdevTemp->startStack();
|
||||||
pdevTemp->parserAuto(callback);
|
m_callback = callback;
|
||||||
|
pdevTemp->parserAuto(sv::Gimbal::gimbalUpdataCallback, this);
|
||||||
|
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
@@ -221,7 +280,7 @@ bool sv::Gimbal::open(PStateInvoke callback)
|
|||||||
bool sv::Gimbal::setHome()
|
bool sv::Gimbal::setHome()
|
||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
if (pdevTemp->dev->setGimabalHome() > 0)
|
if (pdevTemp->setGimabalHome() > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -250,7 +309,7 @@ bool sv::Gimbal::setZoom(double x)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (pdevTemp->dev->setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_STOP, x) > 0)
|
if (pdevTemp->setGimbalZoom(AMOV_GIMBAL_ZOOM_STOP, x) > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -274,7 +333,7 @@ bool sv::Gimbal::setAutoZoom(int state)
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
if (pdevTemp->dev->setGimbalZoom((amovGimbal::AMOV_GIMBAL_ZOOM_T)state, 0.0f) > 0)
|
if (pdevTemp->setGimbalZoom((AMOV_GIMBAL_ZOOM_T)state, 0.0f) > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -300,7 +359,7 @@ bool sv::Gimbal::setAutoFocus(int state)
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
if (pdevTemp->dev->setGimbalFocus((amovGimbal::AMOV_GIMBAL_ZOOM_T)state, 0.0f) > 0)
|
if (pdevTemp->setGimbalFocus((AMOV_GIMBAL_ZOOM_T)state, 0.0f) > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -320,7 +379,7 @@ bool sv::Gimbal::takePhoto()
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
if (pdevTemp->dev->takePic() > 0)
|
if (pdevTemp->takePic() > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -344,21 +403,21 @@ bool sv::Gimbal::takeVideo(int state)
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
amovGimbal::AMOV_GIMBAL_VIDEO_T newState;
|
AMOV_GIMBAL_VIDEO_T newState;
|
||||||
switch (state)
|
switch (state)
|
||||||
{
|
{
|
||||||
case 0:
|
case 0:
|
||||||
newState = amovGimbal::AMOV_GIMBAL_VIDEO_OFF;
|
newState = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
break;
|
break;
|
||||||
case 1:
|
case 1:
|
||||||
newState = amovGimbal::AMOV_GIMBAL_VIDEO_TAKE;
|
newState = AMOV_GIMBAL_VIDEO_TAKE;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
newState = amovGimbal::AMOV_GIMBAL_VIDEO_OFF;
|
newState = AMOV_GIMBAL_VIDEO_OFF;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (pdevTemp->dev->setVideo(newState) > 0)
|
if (pdevTemp->setVideo(newState) > 0)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -379,13 +438,13 @@ int sv::Gimbal::getVideoState()
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
int ret;
|
int ret;
|
||||||
amovGimbal::AMOV_GIMBAL_STATE_T state;
|
AMOV_GIMBAL_STATE_T state;
|
||||||
state = pdevTemp->getGimabalState();
|
state = pdevTemp->getGimabalState();
|
||||||
if (state.video == amovGimbal::AMOV_GIMBAL_VIDEO_TAKE)
|
if (state.video == AMOV_GIMBAL_VIDEO_TAKE)
|
||||||
{
|
{
|
||||||
ret = 1;
|
ret = 1;
|
||||||
}
|
}
|
||||||
else if (state.video == amovGimbal::AMOV_GIMBAL_VIDEO_OFF)
|
else if (state.video == AMOV_GIMBAL_VIDEO_OFF)
|
||||||
{
|
{
|
||||||
ret = 0;
|
ret = 0;
|
||||||
}
|
}
|
||||||
@@ -413,7 +472,7 @@ void sv::Gimbal::setAngleEuler(double roll, double pitch, double yaw,
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
amovGimbal::AMOV_GIMBAL_POS_T temp;
|
AMOV_GIMBAL_POS_T temp;
|
||||||
|
|
||||||
if (pitch_rate == 0.0f)
|
if (pitch_rate == 0.0f)
|
||||||
pitch_rate = 360;
|
pitch_rate = 360;
|
||||||
@@ -425,11 +484,11 @@ void sv::Gimbal::setAngleEuler(double roll, double pitch, double yaw,
|
|||||||
temp.pitch = pitch_rate;
|
temp.pitch = pitch_rate;
|
||||||
temp.roll = roll_rate;
|
temp.roll = roll_rate;
|
||||||
temp.yaw = yaw_rate;
|
temp.yaw = yaw_rate;
|
||||||
pdevTemp->dev->setGimabalFollowSpeed(temp);
|
pdevTemp->setGimabalFollowSpeed(temp);
|
||||||
temp.pitch = pitch;
|
temp.pitch = pitch;
|
||||||
temp.roll = roll;
|
temp.roll = roll;
|
||||||
temp.yaw = yaw;
|
temp.yaw = yaw;
|
||||||
pdevTemp->dev->setGimabalPos(temp);
|
pdevTemp->setGimabalPos(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -444,11 +503,11 @@ void sv::Gimbal::setAngleRateEuler(double roll_rate, double pitch_rate, double y
|
|||||||
{
|
{
|
||||||
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
amovGimbal::gimbal *pdevTemp = (amovGimbal::gimbal *)this->dev;
|
||||||
|
|
||||||
amovGimbal::AMOV_GIMBAL_POS_T temp;
|
AMOV_GIMBAL_POS_T temp;
|
||||||
temp.pitch = pitch_rate;
|
temp.pitch = pitch_rate;
|
||||||
temp.roll = roll_rate;
|
temp.roll = roll_rate;
|
||||||
temp.yaw = yaw_rate;
|
temp.yaw = yaw_rate;
|
||||||
pdevTemp->dev->setGimabalSpeed(temp);
|
pdevTemp->setGimabalSpeed(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
sv::Gimbal::~Gimbal()
|
sv::Gimbal::~Gimbal()
|
||||||
|
|||||||
@@ -3,65 +3,236 @@
|
|||||||
* @Author: L LC @amov
|
* @Author: L LC @amov
|
||||||
* @Date: 2023-04-12 12:22:09
|
* @Date: 2023-04-12 12:22:09
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-04-13 10:17:21
|
* @LastEditTime: 2023-12-05 17:38:59
|
||||||
* @FilePath: /spirecv-gimbal-sdk/gimbal_ctrl/sv_gimbal_io.hpp
|
* @FilePath: /SpireCV/gimbal_ctrl/sv_gimbal_io.hpp
|
||||||
*/
|
*/
|
||||||
#ifndef __SV_GIMABL_IO_H
|
#ifndef __SV_GIMABL_IO_H
|
||||||
#define __SV_GIMABL_IO_H
|
#define __SV_GIMABL_IO_H
|
||||||
|
|
||||||
#include "amov_gimbal.h"
|
#include "amovGimbal/amov_gimbal.h"
|
||||||
#include "serial/serial.h"
|
#include "serial/serial.h"
|
||||||
|
|
||||||
class UART : public amovGimbal::IOStreamBase
|
#include <string.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#if defined(_WIN32)
|
||||||
|
#include <winsock2.h>
|
||||||
|
#include <ws2tcpip.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(__linux__)
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <unistd.h>
|
||||||
|
namespace sv
|
||||||
{
|
{
|
||||||
private:
|
class UART : public amovGimbal::IOStreamBase
|
||||||
serial::Serial *ser;
|
{
|
||||||
|
private:
|
||||||
|
serial::Serial *ser;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
virtual bool open()
|
virtual bool open()
|
||||||
{
|
{
|
||||||
ser->open();
|
ser->open();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
virtual bool close()
|
virtual bool close()
|
||||||
{
|
{
|
||||||
ser->close();
|
ser->close();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
virtual bool isOpen()
|
virtual bool isOpen()
|
||||||
{
|
{
|
||||||
return ser->isOpen();
|
return ser->isOpen();
|
||||||
}
|
}
|
||||||
virtual bool isBusy()
|
virtual bool isBusy()
|
||||||
{
|
{
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
virtual uint32_t inPutBytes(IN uint8_t *byte)
|
||||||
|
{
|
||||||
|
if (ser->read(byte, 1))
|
||||||
|
{
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght)
|
||||||
|
{
|
||||||
|
return ser->write(byte, lenght);
|
||||||
|
}
|
||||||
|
UART(const std::string &port, uint32_t baudrate, serial::Timeout timeout,
|
||||||
|
serial::bytesize_t bytesize, serial::parity_t parity, serial::stopbits_t stopbits,
|
||||||
|
serial::flowcontrol_t flowcontrol)
|
||||||
|
{
|
||||||
|
ser = new serial::Serial(port, baudrate, timeout, bytesize, parity, stopbits, flowcontrol);
|
||||||
|
}
|
||||||
|
~UART()
|
||||||
|
{
|
||||||
|
ser->close();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
virtual bool inPutByte(IN uint8_t *byte)
|
int scoketClose(int scoket)
|
||||||
{
|
{
|
||||||
if (ser->read(byte, 1))
|
#if defined(_WIN32)
|
||||||
|
return closesocket(scoket);
|
||||||
|
#endif
|
||||||
|
#if defined(__linux__)
|
||||||
|
return close(scoket);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
class TCPClient : public amovGimbal::IOStreamBase
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
int scoketFd;
|
||||||
|
sockaddr_in scoketAddr;
|
||||||
|
|
||||||
|
public:
|
||||||
|
virtual bool open()
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
virtual bool close()
|
||||||
}
|
{
|
||||||
|
sv::scoketClose(scoketFd);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
virtual bool isOpen()
|
||||||
|
{
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
virtual bool isBusy()
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
virtual uint32_t inPutBytes(IN uint8_t *byte)
|
||||||
|
{
|
||||||
|
return recv(scoketFd, (char *)byte, 65536, 0);
|
||||||
|
}
|
||||||
|
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght)
|
||||||
|
{
|
||||||
|
return send(scoketFd, (const char *)byte, lenght, 0);
|
||||||
|
}
|
||||||
|
|
||||||
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght)
|
TCPClient(const std::string &addr, const uint16_t port)
|
||||||
{
|
{
|
||||||
return ser->write(byte, lenght);
|
if ((scoketFd = socket(AF_INET, SOCK_STREAM, 0)) == -1)
|
||||||
}
|
{
|
||||||
|
throw std::runtime_error("scoket creat failed");
|
||||||
|
}
|
||||||
|
memset(&scoketAddr, 0, sizeof(scoketAddr));
|
||||||
|
scoketAddr.sin_family = AF_INET;
|
||||||
|
scoketAddr.sin_addr.s_addr = inet_addr(addr.c_str());
|
||||||
|
|
||||||
UART(const std::string &port, uint32_t baudrate, serial::Timeout timeout,
|
if (scoketAddr.sin_addr.s_addr == INADDR_NONE ||
|
||||||
serial::bytesize_t bytesize, serial::parity_t parity, serial::stopbits_t stopbits,
|
scoketAddr.sin_addr.s_addr == INADDR_ANY)
|
||||||
serial::flowcontrol_t flowcontrol)
|
{
|
||||||
|
sv::scoketClose(scoketFd);
|
||||||
|
|
||||||
|
throw std::runtime_error("scoket addr errr");
|
||||||
|
}
|
||||||
|
scoketAddr.sin_port = htons(port);
|
||||||
|
|
||||||
|
if (connect(scoketFd, (struct sockaddr *)&scoketAddr, sizeof(scoketAddr)) != 0)
|
||||||
|
{
|
||||||
|
sv::scoketClose(scoketFd);
|
||||||
|
|
||||||
|
throw std::runtime_error("scoket connect failed !");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
~TCPClient()
|
||||||
|
{
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class UDP : public amovGimbal::IOStreamBase
|
||||||
{
|
{
|
||||||
ser = new serial::Serial(port, baudrate, timeout, bytesize, parity, stopbits, flowcontrol);
|
private:
|
||||||
}
|
int rcvScoketFd, sendScoketFd;
|
||||||
~UART()
|
sockaddr_in rcvScoketAddr, sendScoketAddr;
|
||||||
{
|
|
||||||
ser->close();
|
public:
|
||||||
delete ser;
|
virtual bool open()
|
||||||
}
|
{
|
||||||
};
|
return true;
|
||||||
|
}
|
||||||
|
virtual bool close()
|
||||||
|
{
|
||||||
|
sv::scoketClose(rcvScoketFd);
|
||||||
|
sv::scoketClose(sendScoketFd);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
virtual bool isOpen()
|
||||||
|
{
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
virtual bool isBusy()
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
virtual uint32_t inPutBytes(IN uint8_t *byte)
|
||||||
|
{
|
||||||
|
sockaddr_in remoteAddr;
|
||||||
|
int len = sizeof(remoteAddr);
|
||||||
|
|
||||||
|
return recvfrom(rcvScoketFd, (char *)byte, 65536, 0,
|
||||||
|
(struct sockaddr *)&remoteAddr, reinterpret_cast<socklen_t *>(&len));
|
||||||
|
}
|
||||||
|
virtual uint32_t outPutBytes(IN uint8_t *byte, uint32_t lenght)
|
||||||
|
{
|
||||||
|
return sendto(sendScoketFd, (const char *)byte, lenght, 0,
|
||||||
|
(struct sockaddr *)&sendScoketAddr, sizeof(sendScoketAddr));
|
||||||
|
}
|
||||||
|
|
||||||
|
UDP(const std::string &remoteAddr, const uint16_t rcvPort, uint16_t sendPort)
|
||||||
|
{
|
||||||
|
if ((rcvScoketFd = socket(AF_INET, SOCK_DGRAM, 0)) == -1 ||
|
||||||
|
(sendScoketFd = socket(AF_INET, SOCK_DGRAM, 0)) == -1)
|
||||||
|
{
|
||||||
|
sv::scoketClose(rcvScoketFd);
|
||||||
|
sv::scoketClose(sendScoketFd);
|
||||||
|
throw std::runtime_error("scoket creat failed");
|
||||||
|
}
|
||||||
|
memset(&rcvScoketAddr, 0, sizeof(rcvScoketAddr));
|
||||||
|
memset(&sendScoketAddr, 0, sizeof(sendScoketAddr));
|
||||||
|
sendScoketAddr.sin_family = AF_INET;
|
||||||
|
sendScoketAddr.sin_addr.s_addr = inet_addr(remoteAddr.c_str());
|
||||||
|
sendScoketAddr.sin_port = htons(sendPort);
|
||||||
|
|
||||||
|
if (sendScoketAddr.sin_addr.s_addr == INADDR_NONE ||
|
||||||
|
sendScoketAddr.sin_addr.s_addr == INADDR_ANY)
|
||||||
|
{
|
||||||
|
sv::scoketClose(sendScoketFd);
|
||||||
|
|
||||||
|
throw std::runtime_error("scoket addr errr");
|
||||||
|
}
|
||||||
|
|
||||||
|
rcvScoketAddr.sin_family = AF_INET;
|
||||||
|
rcvScoketAddr.sin_addr.s_addr = INADDR_ANY;
|
||||||
|
rcvScoketAddr.sin_port = htons(rcvPort);
|
||||||
|
|
||||||
|
if (rcvScoketAddr.sin_addr.s_addr == INADDR_NONE)
|
||||||
|
{
|
||||||
|
sv::scoketClose(rcvScoketFd);
|
||||||
|
|
||||||
|
throw std::runtime_error("scoket addr errr");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (bind(rcvScoketFd, (struct sockaddr *)&rcvScoketAddr, sizeof(rcvScoketAddr)) == -1)
|
||||||
|
{
|
||||||
|
sv::scoketClose(rcvScoketFd);
|
||||||
|
|
||||||
|
throw std::runtime_error("scoket bind failed !");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
~UDP()
|
||||||
|
{
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
79
include/sv_camera.h
Normal file
79
include/sv_camera.h
Normal 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
|
||||||
@@ -3,8 +3,8 @@
|
|||||||
* @Author: jario-jin @amov
|
* @Author: jario-jin @amov
|
||||||
* @Date: 2023-04-12 09:12:52
|
* @Date: 2023-04-12 09:12:52
|
||||||
* @LastEditors: L LC @amov
|
* @LastEditors: L LC @amov
|
||||||
* @LastEditTime: 2023-04-18 11:49:27
|
* @LastEditTime: 2023-12-05 17:25:40
|
||||||
* @FilePath: /spirecv-gimbal-sdk/include/sv_gimbal.h
|
* @FilePath: /SpireCV/include/sv_gimbal.h
|
||||||
*/
|
*/
|
||||||
#ifndef __SV_GIMBAL__
|
#ifndef __SV_GIMBAL__
|
||||||
#define __SV_GIMBAL__
|
#define __SV_GIMBAL__
|
||||||
@@ -27,14 +27,26 @@ namespace sv
|
|||||||
G1,
|
G1,
|
||||||
Q10f,
|
Q10f,
|
||||||
AT10,
|
AT10,
|
||||||
|
GX40,
|
||||||
};
|
};
|
||||||
enum class GimbalLink
|
enum class GimbalLink : int
|
||||||
{
|
{
|
||||||
SERIAL,
|
NONE = 0x00,
|
||||||
ETHERNET_TCP,
|
SERIAL = 0x01,
|
||||||
ETHERNET_UDP
|
ETHERNET_TCP = 0x02,
|
||||||
|
ETHERNET_UDP = 0x04,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
constexpr GimbalLink operator|(GimbalLink a, GimbalLink b)
|
||||||
|
{
|
||||||
|
return static_cast<GimbalLink>(static_cast<int>(a) | static_cast<int>(b));
|
||||||
|
}
|
||||||
|
|
||||||
|
constexpr GimbalLink operator&(GimbalLink a, GimbalLink b)
|
||||||
|
{
|
||||||
|
return static_cast<GimbalLink>(static_cast<int>(a) & static_cast<int>(b));
|
||||||
|
}
|
||||||
|
|
||||||
enum class GimablSerialByteSize
|
enum class GimablSerialByteSize
|
||||||
{
|
{
|
||||||
FIVE_BYTES = 5,
|
FIVE_BYTES = 5,
|
||||||
@@ -83,6 +95,7 @@ namespace sv
|
|||||||
// Device pointers
|
// Device pointers
|
||||||
void *dev;
|
void *dev;
|
||||||
void *IO;
|
void *IO;
|
||||||
|
PStateInvoke m_callback;
|
||||||
|
|
||||||
// Generic serial interface parameters list & default parameters
|
// Generic serial interface parameters list & default parameters
|
||||||
std::string m_serial_port = "/dev/ttyUSB0";
|
std::string m_serial_port = "/dev/ttyUSB0";
|
||||||
@@ -94,8 +107,10 @@ namespace sv
|
|||||||
int m_serial_timeout = 500;
|
int m_serial_timeout = 500;
|
||||||
|
|
||||||
// Ethernet interface parameters list & default parameters
|
// Ethernet interface parameters list & default parameters
|
||||||
std::string m_net_ip = "192.168.2.64";
|
std::string m_net_ip = "192.168.144.121";
|
||||||
int m_net_port = 9090;
|
int m_net_port = 2332;
|
||||||
|
int m_net_recv_port = 2338;
|
||||||
|
int m_net_send_port = 2337;
|
||||||
|
|
||||||
GimbalType m_gimbal_type;
|
GimbalType m_gimbal_type;
|
||||||
GimbalLink m_gimbal_link;
|
GimbalLink m_gimbal_link;
|
||||||
@@ -104,6 +119,14 @@ namespace sv
|
|||||||
static std::mutex IOListMutex;
|
static std::mutex IOListMutex;
|
||||||
static void *creatIO(Gimbal *dev);
|
static void *creatIO(Gimbal *dev);
|
||||||
static void removeIO(Gimbal *dev);
|
static void removeIO(Gimbal *dev);
|
||||||
|
|
||||||
|
static void gimbalUpdataCallback(double frameAngleRoll, double frameAnglePitch, double frameAngleYaw,
|
||||||
|
double imuAngleRoll, double imuAnglePitch, double imuAngleYaw,
|
||||||
|
double fovX, double fovY, void *handle)
|
||||||
|
{
|
||||||
|
((Gimbal *)(handle))->m_callback(frameAngleRoll, frameAnglePitch, frameAngleYaw, imuAngleRoll, imuAnglePitch, imuAngleYaw, fovX, fovY);
|
||||||
|
}
|
||||||
|
|
||||||
public:
|
public:
|
||||||
//! Constructor
|
//! Constructor
|
||||||
/*!
|
/*!
|
||||||
@@ -125,7 +148,10 @@ namespace sv
|
|||||||
|
|
||||||
// set Ethernet interface parameters
|
// set Ethernet interface parameters
|
||||||
void setNetIp(const std::string &ip);
|
void setNetIp(const std::string &ip);
|
||||||
void setNetPort(const int &port);
|
// set tcp port
|
||||||
|
void setTcpNetPort(const int &port);
|
||||||
|
// set udp port
|
||||||
|
void setUdpNetPort(const int &recvPort, const int &sendPort);
|
||||||
|
|
||||||
// Create a device instance
|
// Create a device instance
|
||||||
void setStateCallback(PStateInvoke callback);
|
void setStateCallback(PStateInvoke callback);
|
||||||
|
|||||||
@@ -8,29 +8,36 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
#include <chrono>
|
#include <chrono>
|
||||||
|
|
||||||
|
namespace sv
|
||||||
namespace sv {
|
|
||||||
|
|
||||||
class VeriDetectorCUDAImpl;
|
|
||||||
|
|
||||||
class VeriDetector : public LandingMarkerDetectorBase
|
|
||||||
{
|
{
|
||||||
public:
|
|
||||||
VeriDetector();
|
|
||||||
~VeriDetector();
|
|
||||||
|
|
||||||
void detect(cv::Mat img1_, cv::Mat img2_, TargetsInFrame &tgts_);
|
class VeriDetectorCUDAImpl;
|
||||||
|
|
||||||
protected:
|
class VeriDetector : public LandingMarkerDetectorBase
|
||||||
bool setupImpl();
|
{
|
||||||
void roiCNN(
|
public:
|
||||||
std::vector<cv::Mat>& input_rois_,
|
VeriDetector();
|
||||||
std::vector<int>& output_labels_
|
~VeriDetector();
|
||||||
);
|
|
||||||
|
|
||||||
VeriDetectorCUDAImpl* _cuda_impl;
|
void detect(cv::Mat img_, const cv::Rect &bounding_box_, sv::Target &tgt);
|
||||||
};
|
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void _load();
|
||||||
|
bool setupImpl();
|
||||||
|
void roiCNN(
|
||||||
|
std::vector<cv::Mat> &input_rois_,
|
||||||
|
std::vector<float> &output_labels_);
|
||||||
|
void getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz);
|
||||||
|
|
||||||
|
std::string vehicle_id;
|
||||||
|
|
||||||
|
// Save the target bounding box for each frame.
|
||||||
|
std::vector<float> targetSz = {0, 0}; // H and W of bounding box
|
||||||
|
std::vector<float> targetPos = {0, 0}; // center point of bounding box (x, y)
|
||||||
|
|
||||||
|
|
||||||
|
VeriDetectorCUDAImpl *_cuda_impl;
|
||||||
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -90,6 +90,9 @@ public:
|
|||||||
double los_ay;
|
double los_ay;
|
||||||
//! The angle of the target in the image coordinate system, (unit: degree) [-180, 180].
|
//! The angle of the target in the image coordinate system, (unit: degree) [-180, 180].
|
||||||
double yaw_a;
|
double yaw_a;
|
||||||
|
|
||||||
|
//! Similarity, Confidence, (0, 1]
|
||||||
|
double sim_score;
|
||||||
|
|
||||||
//! Whether the height&width of the target can be obtained.
|
//! Whether the height&width of the target can be obtained.
|
||||||
bool has_hw;
|
bool has_hw;
|
||||||
@@ -323,59 +326,59 @@ protected:
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
enum class CameraType {NONE, WEBCAM, G1, Q10, MIPI};
|
// enum class CameraType {NONE, WEBCAM, V4L2CAM, G1, Q10, MIPI, GX40};
|
||||||
|
|
||||||
class CameraBase {
|
// class CameraBase {
|
||||||
public:
|
// public:
|
||||||
CameraBase(CameraType type=CameraType::NONE, int id=0);
|
// CameraBase(CameraType type=CameraType::NONE, int id=0);
|
||||||
~CameraBase();
|
// ~CameraBase();
|
||||||
void open(CameraType type=CameraType::WEBCAM, int id=0);
|
// void open(CameraType type=CameraType::WEBCAM, int id=0);
|
||||||
bool read(cv::Mat& image);
|
// bool read(cv::Mat& image);
|
||||||
void release();
|
// void release();
|
||||||
|
|
||||||
int getW();
|
// int getW();
|
||||||
int getH();
|
// int getH();
|
||||||
int getFps();
|
// int getFps();
|
||||||
std::string getIp();
|
// std::string getIp();
|
||||||
int getPort();
|
// int getPort();
|
||||||
double getBrightness();
|
// double getBrightness();
|
||||||
double getContrast();
|
// double getContrast();
|
||||||
double getSaturation();
|
// double getSaturation();
|
||||||
double getHue();
|
// double getHue();
|
||||||
double getExposure();
|
// double getExposure();
|
||||||
bool isRunning();
|
// bool isRunning();
|
||||||
void setWH(int width, int height);
|
// void setWH(int width, int height);
|
||||||
void setFps(int fps);
|
// void setFps(int fps);
|
||||||
void setIp(std::string ip);
|
// void setIp(std::string ip);
|
||||||
void setPort(int port);
|
// void setPort(int port);
|
||||||
void setBrightness(double brightness);
|
// void setBrightness(double brightness);
|
||||||
void setContrast(double contrast);
|
// void setContrast(double contrast);
|
||||||
void setSaturation(double saturation);
|
// void setSaturation(double saturation);
|
||||||
void setHue(double hue);
|
// void setHue(double hue);
|
||||||
void setExposure(double exposure);
|
// void setExposure(double exposure);
|
||||||
protected:
|
// protected:
|
||||||
virtual void openImpl();
|
// virtual void openImpl();
|
||||||
void _run();
|
// void _run();
|
||||||
|
|
||||||
bool _is_running;
|
// bool _is_running;
|
||||||
bool _is_updated;
|
// bool _is_updated;
|
||||||
std::thread _tt;
|
// std::thread _tt;
|
||||||
cv::VideoCapture _cap;
|
// cv::VideoCapture _cap;
|
||||||
cv::Mat _frame;
|
// cv::Mat _frame;
|
||||||
CameraType _type;
|
// CameraType _type;
|
||||||
int _camera_id;
|
// int _camera_id;
|
||||||
|
|
||||||
int _width;
|
// int _width;
|
||||||
int _height;
|
// int _height;
|
||||||
int _fps;
|
// int _fps;
|
||||||
std::string _ip;
|
// std::string _ip;
|
||||||
int _port;
|
// int _port;
|
||||||
double _brightness;
|
// double _brightness;
|
||||||
double _contrast;
|
// double _contrast;
|
||||||
double _saturation;
|
// double _saturation;
|
||||||
double _hue;
|
// double _hue;
|
||||||
double _exposure;
|
// double _exposure;
|
||||||
};
|
// };
|
||||||
|
|
||||||
|
|
||||||
void drawTargetsInFrame(
|
void drawTargetsInFrame(
|
||||||
|
|||||||
@@ -1,3 +1,4 @@
|
|||||||
|
#if 0
|
||||||
#ifndef __SV_VIDEO_INPUT__
|
#ifndef __SV_VIDEO_INPUT__
|
||||||
#define __SV_VIDEO_INPUT__
|
#define __SV_VIDEO_INPUT__
|
||||||
|
|
||||||
@@ -25,3 +26,4 @@ protected:
|
|||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
|||||||
@@ -18,9 +18,9 @@ const static int kInputH_HD = 1280;
|
|||||||
const static int kInputW_HD = 1280;
|
const static int kInputW_HD = 1280;
|
||||||
const static int kOutputSize = kMaxNumOutputBbox * sizeof(Detection) / sizeof(float) + 1;
|
const static int kOutputSize = kMaxNumOutputBbox * sizeof(Detection) / sizeof(float) + 1;
|
||||||
|
|
||||||
bool parse_args(int argc, char** argv, std::string& wts, std::string& engine, bool& is_p6, float& gd, float& gw, std::string& img_dir, int& n_classes) {
|
bool parse_args(int argc, char** argv, std::string& wts, std::string& engine, bool& is_p6, float& gd, float& gw, std::string& img_dir, int& n_classes, int& n_batch) {
|
||||||
if (argc < 4) return false;
|
if (argc < 4) return false;
|
||||||
if (std::string(argv[1]) == "-s" && (argc == 6 || argc == 8)) {
|
if (std::string(argv[1]) == "-s" && (argc == 6 || argc == 7 || argc == 8)) {
|
||||||
wts = std::string(argv[2]);
|
wts = std::string(argv[2]);
|
||||||
engine = std::string(argv[3]);
|
engine = std::string(argv[3]);
|
||||||
n_classes = atoi(argv[4]);
|
n_classes = atoi(argv[4]);
|
||||||
@@ -51,6 +51,9 @@ bool parse_args(int argc, char** argv, std::string& wts, std::string& engine, bo
|
|||||||
if (net.size() == 2 && net[1] == '6') {
|
if (net.size() == 2 && net[1] == '6') {
|
||||||
is_p6 = true;
|
is_p6 = true;
|
||||||
}
|
}
|
||||||
|
if (argc == 7) {
|
||||||
|
n_batch = atoi(argv[6]);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@@ -99,18 +102,20 @@ int main(int argc, char** argv) {
|
|||||||
float gd = 0.0f, gw = 0.0f;
|
float gd = 0.0f, gw = 0.0f;
|
||||||
std::string img_dir;
|
std::string img_dir;
|
||||||
int n_classes;
|
int n_classes;
|
||||||
|
int n_batch = 1;
|
||||||
|
|
||||||
if (!parse_args(argc, argv, wts_name, engine_name, is_p6, gd, gw, img_dir, n_classes)) {
|
if (!parse_args(argc, argv, wts_name, engine_name, is_p6, gd, gw, img_dir, n_classes, n_batch)) {
|
||||||
std::cerr << "arguments not right!" << std::endl;
|
std::cerr << "arguments not right!" << std::endl;
|
||||||
std::cerr << "./SpireCVDet -s [.wts] [.engine] n_classes [n/s/m/l/x/n6/s6/m6/l6/x6 or c/c6 gd gw] // serialize model to plan file" << std::endl;
|
std::cerr << "./SpireCVDet -s [.wts] [.engine] n_classes [n/s/m/l/x/n6/s6/m6/l6/x6 or c/c6 gd gw] // serialize model to plan file" << std::endl;
|
||||||
// std::cerr << "./SpireCVDet -d [.engine] ../images // deserialize plan file and run inference" << std::endl;
|
// std::cerr << "./SpireCVDet -d [.engine] ../images // deserialize plan file and run inference" << std::endl;
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
std::cout << "n_classes: " << n_classes << std::endl;
|
std::cout << "n_classes: " << n_classes << std::endl;
|
||||||
|
std::cout << "max_batch: " << n_batch << std::endl;
|
||||||
|
|
||||||
// Create a model using the API directly and serialize it to a file
|
// Create a model using the API directly and serialize it to a file
|
||||||
if (!wts_name.empty()) {
|
if (!wts_name.empty()) {
|
||||||
serialize_engine(kBatchSize, is_p6, gd, gw, wts_name, engine_name, n_classes);
|
serialize_engine(n_batch, is_p6, gd, gw, wts_name, engine_name, n_classes);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -18,44 +18,47 @@ const static int kInputW = 640;
|
|||||||
const static int kOutputSize1 = kMaxNumOutputBbox * sizeof(Detection) / sizeof(float) + 1;
|
const static int kOutputSize1 = kMaxNumOutputBbox * sizeof(Detection) / sizeof(float) + 1;
|
||||||
const static int kOutputSize2 = 32 * (kInputH / 4) * (kInputW / 4);
|
const static int kOutputSize2 = 32 * (kInputH / 4) * (kInputW / 4);
|
||||||
|
|
||||||
bool parse_args(int argc, char** argv, std::string& wts, std::string& engine, float& gd, float& gw, std::string& img_dir, std::string& labels_filename, int& n_classes) {
|
bool parse_args(int argc, char** argv, std::string& wts, std::string& engine, float& gd, float& gw, std::string& img_dir, std::string& labels_filename, int& n_classes, int& n_batch) {
|
||||||
if (argc < 4) return false;
|
if (argc < 4) return false;
|
||||||
if (std::string(argv[1]) == "-s" && (argc == 6 || argc == 8)) {
|
if (std::string(argv[1]) == "-s" && (argc == 6 || argc == 7 || argc == 8)) {
|
||||||
wts = std::string(argv[2]);
|
wts = std::string(argv[2]);
|
||||||
engine = std::string(argv[3]);
|
engine = std::string(argv[3]);
|
||||||
n_classes = atoi(argv[4]);
|
n_classes = atoi(argv[4]);
|
||||||
if (n_classes < 1)
|
if (n_classes < 1)
|
||||||
return false;
|
return false;
|
||||||
auto net = std::string(argv[5]);
|
auto net = std::string(argv[5]);
|
||||||
if (net[0] == 'n') {
|
if (net[0] == 'n') {
|
||||||
gd = 0.33;
|
gd = 0.33;
|
||||||
gw = 0.25;
|
gw = 0.25;
|
||||||
} else if (net[0] == 's') {
|
} else if (net[0] == 's') {
|
||||||
gd = 0.33;
|
gd = 0.33;
|
||||||
gw = 0.50;
|
gw = 0.50;
|
||||||
} else if (net[0] == 'm') {
|
} else if (net[0] == 'm') {
|
||||||
gd = 0.67;
|
gd = 0.67;
|
||||||
gw = 0.75;
|
gw = 0.75;
|
||||||
} else if (net[0] == 'l') {
|
} else if (net[0] == 'l') {
|
||||||
gd = 1.0;
|
gd = 1.0;
|
||||||
gw = 1.0;
|
gw = 1.0;
|
||||||
} else if (net[0] == 'x') {
|
} else if (net[0] == 'x') {
|
||||||
gd = 1.33;
|
gd = 1.33;
|
||||||
gw = 1.25;
|
gw = 1.25;
|
||||||
} else if (net[0] == 'c' && argc == 8) {
|
} else if (net[0] == 'c' && argc == 8) {
|
||||||
gd = atof(argv[6]);
|
gd = atof(argv[6]);
|
||||||
gw = atof(argv[7]);
|
gw = atof(argv[7]);
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} else if (std::string(argv[1]) == "-d" && argc == 5) {
|
|
||||||
engine = std::string(argv[2]);
|
|
||||||
img_dir = std::string(argv[3]);
|
|
||||||
labels_filename = std::string(argv[4]);
|
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
if (argc == 7) {
|
||||||
|
n_batch = atoi(argv[6]);
|
||||||
|
}
|
||||||
|
} else if (std::string(argv[1]) == "-d" && argc == 5) {
|
||||||
|
engine = std::string(argv[2]);
|
||||||
|
img_dir = std::string(argv[3]);
|
||||||
|
labels_filename = std::string(argv[4]);
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -98,19 +101,21 @@ int main(int argc, char** argv) {
|
|||||||
std::string labels_filename = "";
|
std::string labels_filename = "";
|
||||||
float gd = 0.0f, gw = 0.0f;
|
float gd = 0.0f, gw = 0.0f;
|
||||||
int n_classes;
|
int n_classes;
|
||||||
|
int n_batch = 1;
|
||||||
|
|
||||||
std::string img_dir;
|
std::string img_dir;
|
||||||
if (!parse_args(argc, argv, wts_name, engine_name, gd, gw, img_dir, labels_filename, n_classes)) {
|
if (!parse_args(argc, argv, wts_name, engine_name, gd, gw, img_dir, labels_filename, n_classes, n_batch)) {
|
||||||
std::cerr << "arguments not right!" << std::endl;
|
std::cerr << "arguments not right!" << std::endl;
|
||||||
std::cerr << "./SpireCVSeg -s [.wts] [.engine] n_classes [n/s/m/l/x or c gd gw] // serialize model to plan file" << std::endl;
|
std::cerr << "./SpireCVSeg -s [.wts] [.engine] n_classes [n/s/m/l/x or c gd gw] // serialize model to plan file" << std::endl;
|
||||||
// std::cerr << "./SpireCVSeg -d [.engine] ../images coco.txt // deserialize plan file, read the labels file and run inference" << std::endl;
|
// std::cerr << "./SpireCVSeg -d [.engine] ../images coco.txt // deserialize plan file, read the labels file and run inference" << std::endl;
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
std::cout << "n_classes: " << n_classes << std::endl;
|
std::cout << "n_classes: " << n_classes << std::endl;
|
||||||
|
std::cout << "max_batch: " << n_batch << std::endl;
|
||||||
|
|
||||||
// Create a model using the API directly and serialize it to a file
|
// Create a model using the API directly and serialize it to a file
|
||||||
if (!wts_name.empty()) {
|
if (!wts_name.empty()) {
|
||||||
serialize_engine(kBatchSize, gd, gw, wts_name, engine_name, n_classes);
|
serialize_engine(n_batch, gd, gw, wts_name, engine_name, n_classes);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -36,8 +36,11 @@ the use of this software, even if advised of the possibility of such damage.
|
|||||||
#include <opencv2/imgproc.hpp>
|
#include <opencv2/imgproc.hpp>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <sv_world.h>
|
||||||
#include "aruco_samples_utility.hpp"
|
#include "aruco_samples_utility.hpp"
|
||||||
|
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace cv;
|
using namespace cv;
|
||||||
|
|
||||||
@@ -58,7 +61,10 @@ const char* keys =
|
|||||||
"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
|
"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
|
||||||
"{cd | | Input file with custom dictionary }"
|
"{cd | | Input file with custom dictionary }"
|
||||||
"{@outfile |<none> | Output file with calibrated camera parameters }"
|
"{@outfile |<none> | Output file with calibrated camera parameters }"
|
||||||
"{v | | Input from video file, if ommited, input comes from camera }"
|
"{imh | | Camera Image Height }"
|
||||||
|
"{imw | | Camera Image Width }"
|
||||||
|
"{fps | | Camera FPS }"
|
||||||
|
"{tp | | 1:WEBCAM, 2:V4L2CAM, 3:G1, 4:Q10, 5:MIPI, 6:GX40 }"
|
||||||
"{ci | 0 | Camera id if input doesnt come from video (-v) }"
|
"{ci | 0 | Camera id if input doesnt come from video (-v) }"
|
||||||
"{dp | | File of marker detector parameters }"
|
"{dp | | File of marker detector parameters }"
|
||||||
"{rs | false | Apply refind strategy }"
|
"{rs | false | Apply refind strategy }"
|
||||||
@@ -107,26 +113,51 @@ int main(int argc, char *argv[]) {
|
|||||||
|
|
||||||
bool refindStrategy = parser.get<bool>("rs");
|
bool refindStrategy = parser.get<bool>("rs");
|
||||||
int camId = parser.get<int>("ci");
|
int camId = parser.get<int>("ci");
|
||||||
String video;
|
int imW = 800;
|
||||||
|
int imH = 600;
|
||||||
|
int fps = 30;
|
||||||
|
int tp = 1;
|
||||||
|
|
||||||
if(parser.has("v")) {
|
if(parser.has("imh")) {
|
||||||
video = parser.get<String>("v");
|
imH = parser.get<int>("imh");
|
||||||
}
|
}
|
||||||
|
if(parser.has("imw")) {
|
||||||
|
imW = parser.get<int>("imw");
|
||||||
|
}
|
||||||
|
if(parser.has("fps")) {
|
||||||
|
fps = parser.get<int>("fps");
|
||||||
|
}
|
||||||
|
if(parser.has("tp")) {
|
||||||
|
tp = parser.get<int>("tp");
|
||||||
|
}
|
||||||
|
sv::CameraType c_type = sv::CameraType::WEBCAM;
|
||||||
|
if (2 == tp)
|
||||||
|
c_type = sv::CameraType::V4L2CAM;
|
||||||
|
else if (3 == tp)
|
||||||
|
c_type = sv::CameraType::G1;
|
||||||
|
else if (4 == tp)
|
||||||
|
c_type = sv::CameraType::Q10;
|
||||||
|
else if (5 == tp)
|
||||||
|
c_type = sv::CameraType::MIPI;
|
||||||
|
else if (6 == tp)
|
||||||
|
c_type = sv::CameraType::GX40;
|
||||||
|
|
||||||
if(!parser.check()) {
|
if(!parser.check()) {
|
||||||
parser.printErrors();
|
parser.printErrors();
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
VideoCapture inputVideo;
|
// VideoCapture inputVideo;
|
||||||
int waitTime;
|
sv::Camera inputVideo(c_type);
|
||||||
if(!video.empty()) {
|
inputVideo.setIndex(camId);
|
||||||
inputVideo.open(video);
|
inputVideo.setStream("192.168.144.64",554);
|
||||||
waitTime = 0;
|
|
||||||
} else {
|
inputVideo.setWH(imW, imH);
|
||||||
inputVideo.open(camId);
|
inputVideo.setFps(fps);
|
||||||
waitTime = 10;
|
|
||||||
}
|
inputVideo.open();
|
||||||
|
|
||||||
|
int waitTime = 10;
|
||||||
|
|
||||||
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(0);
|
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(0);
|
||||||
if (parser.has("d")) {
|
if (parser.has("d")) {
|
||||||
@@ -156,9 +187,9 @@ int main(int argc, char *argv[]) {
|
|||||||
vector< Mat > allImgs;
|
vector< Mat > allImgs;
|
||||||
Size imgSize;
|
Size imgSize;
|
||||||
|
|
||||||
while(inputVideo.grab()) {
|
while(1) {
|
||||||
Mat image, imageCopy;
|
Mat image, imageCopy;
|
||||||
inputVideo.retrieve(image);
|
inputVideo.read(image);
|
||||||
|
|
||||||
vector< int > ids;
|
vector< int > ids;
|
||||||
vector< vector< Point2f > > corners, rejected;
|
vector< vector< Point2f > > corners, rejected;
|
||||||
|
|||||||
255
samples/calib/create_marker.cpp
Normal file
255
samples/calib/create_marker.cpp
Normal file
@@ -0,0 +1,255 @@
|
|||||||
|
#include <opencv2/highgui.hpp>
|
||||||
|
#include <opencv2/objdetect/aruco_detector.hpp>
|
||||||
|
#include <iostream>
|
||||||
|
#include "aruco_samples_utility.hpp"
|
||||||
|
|
||||||
|
using namespace cv;
|
||||||
|
|
||||||
|
namespace {
|
||||||
|
const char* about = "Create an ArUco marker image";
|
||||||
|
|
||||||
|
//! [aruco_create_markers_keys]
|
||||||
|
const char* keys =
|
||||||
|
"{@outfile |<none> | Output image }"
|
||||||
|
"{d | | dictionary: DICT_4X4_50=0, DICT_4X4_100=1, DICT_4X4_250=2,"
|
||||||
|
"DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5, DICT_5X5_250=6, DICT_5X5_1000=7, "
|
||||||
|
"DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11, DICT_7X7_50=12,"
|
||||||
|
"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
|
||||||
|
"{cd | | Input file with custom dictionary }"
|
||||||
|
"{id | | Marker id in the dictionary }"
|
||||||
|
"{ms | 200 | Marker size in pixels }"
|
||||||
|
"{bs | 50 | Border size in pixels }"
|
||||||
|
"{lp | 50 | Landing Pad Unit in pixels }"
|
||||||
|
"{bb | 1 | Number of bits in marker borders }"
|
||||||
|
"{si | false | show generated image }";
|
||||||
|
}
|
||||||
|
//! [aruco_create_markers_keys]
|
||||||
|
|
||||||
|
|
||||||
|
Mat create_marker_with_borders(aruco::Dictionary& dictionary, int markerId, int markerSize, int borderBits, int borderSize) {
|
||||||
|
Mat tmpImg;
|
||||||
|
aruco::generateImageMarker(dictionary, markerId, markerSize, tmpImg, borderBits);
|
||||||
|
Mat tmpImgCopy = Mat::ones(borderSize * 2 + markerSize, borderSize * 2 + markerSize, CV_8UC1) * 255;
|
||||||
|
tmpImg.copyTo(tmpImgCopy(Rect(borderSize, borderSize, markerSize, markerSize)));
|
||||||
|
tmpImg = tmpImgCopy;
|
||||||
|
return tmpImg;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int main(int argc, char *argv[]) {
|
||||||
|
CommandLineParser parser(argc, argv, keys);
|
||||||
|
parser.about(about);
|
||||||
|
|
||||||
|
if(argc < 4) {
|
||||||
|
parser.printMessage();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int markerId = parser.get<int>("id");
|
||||||
|
int borderBits = parser.get<int>("bb");
|
||||||
|
int markerSize = parser.get<int>("ms");
|
||||||
|
bool showImage = parser.get<bool>("si");
|
||||||
|
|
||||||
|
int borderSize = 0;
|
||||||
|
if (parser.has("bs")) {
|
||||||
|
borderSize = parser.get<int>("bs");
|
||||||
|
}
|
||||||
|
int landingPadUnit = 0;
|
||||||
|
if (parser.has("lp")) {
|
||||||
|
landingPadUnit = parser.get<int>("lp");
|
||||||
|
borderSize = landingPadUnit;
|
||||||
|
borderBits = 1;
|
||||||
|
markerSize = landingPadUnit * 4;
|
||||||
|
}
|
||||||
|
|
||||||
|
String out = parser.get<String>(0);
|
||||||
|
|
||||||
|
if(!parser.check()) {
|
||||||
|
parser.printErrors();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(0);
|
||||||
|
if (parser.has("d")) {
|
||||||
|
int dictionaryId = parser.get<int>("d");
|
||||||
|
dictionary = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(dictionaryId));
|
||||||
|
}
|
||||||
|
else if (parser.has("cd")) {
|
||||||
|
FileStorage fs(parser.get<std::string>("cd"), FileStorage::READ);
|
||||||
|
bool readOk = dictionary.aruco::Dictionary::readDictionary(fs.root());
|
||||||
|
if(!readOk) {
|
||||||
|
std::cerr << "Invalid dictionary file" << std::endl;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
std::cerr << "Dictionary not specified" << std::endl;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
Mat markerImg;
|
||||||
|
aruco::generateImageMarker(dictionary, markerId, markerSize, markerImg, borderBits);
|
||||||
|
if (borderSize > 0) {
|
||||||
|
Mat markerImgCopy = Mat::ones(borderSize * 2 + markerSize, borderSize * 2 + markerSize, CV_8UC1) * 255;
|
||||||
|
markerImg.copyTo(markerImgCopy(Rect(borderSize, borderSize, markerSize, markerSize)));
|
||||||
|
markerImg = markerImgCopy;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (landingPadUnit > 0) {
|
||||||
|
Mat markerImgBIG = Mat::ones(landingPadUnit * 62, landingPadUnit * 62, CV_8UC1) * 255;
|
||||||
|
markerId = 0;
|
||||||
|
markerSize = landingPadUnit * 4;
|
||||||
|
borderSize = landingPadUnit;
|
||||||
|
int newSize = markerSize + borderSize * 2;
|
||||||
|
|
||||||
|
for (int i=0; i<3; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(i * landingPadUnit * 5, 0, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<5; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 18 + i * landingPadUnit * 5, 0, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<3; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 46 + i * landingPadUnit * 5, 0, newSize, newSize)));
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i=0; i<2; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 56, landingPadUnit * 5 + i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<5; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 56, landingPadUnit * 18 + i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<3; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 56, landingPadUnit * 46 + i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i=0; i<2; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 51 - i * landingPadUnit * 5, landingPadUnit * 56, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<5; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 38 - i * landingPadUnit * 5, landingPadUnit * 56, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<3; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 10 - i * landingPadUnit * 5, landingPadUnit * 56, newSize, newSize)));
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i=0; i<2; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(0, landingPadUnit * 51 - i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<5; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(0, landingPadUnit * 38 - i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
for (int i=0; i<2; i++) {
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(0, landingPadUnit * 10 - i * landingPadUnit * 5, newSize, newSize)));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 23, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 33, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 33, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 23, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 18, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 38, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 38, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 18, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 5, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 51, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 51, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 5, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 10, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 46, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 28, landingPadUnit * 46, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 10, landingPadUnit * 28, newSize, newSize)));
|
||||||
|
|
||||||
|
markerId = 90;
|
||||||
|
markerSize = landingPadUnit * 4 * 4;
|
||||||
|
borderSize = landingPadUnit * 4;
|
||||||
|
newSize = markerSize + borderSize * 2;
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 5, landingPadUnit * 5, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 5 + newSize + landingPadUnit * 4, landingPadUnit * 5, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 5, landingPadUnit * 5 + newSize + landingPadUnit * 4, newSize, newSize)));
|
||||||
|
markerId += 1;
|
||||||
|
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
|
||||||
|
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 5 + newSize + landingPadUnit * 4, landingPadUnit * 5 + newSize + landingPadUnit * 4, newSize, newSize)));
|
||||||
|
|
||||||
|
markerImg = Mat::ones(landingPadUnit * 64, landingPadUnit * 64, CV_8UC1) * 255;
|
||||||
|
markerImgBIG.copyTo(markerImg(Rect(landingPadUnit, landingPadUnit, landingPadUnit * 62, landingPadUnit * 62)));
|
||||||
|
}
|
||||||
|
|
||||||
|
if(showImage) {
|
||||||
|
imshow("marker", markerImg);
|
||||||
|
waitKey(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
imwrite(out, markerImg);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -12,10 +13,12 @@ int main(int argc, char *argv[]) {
|
|||||||
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
|
||||||
|
cap.setIndex(0);
|
||||||
|
cap.setWH(ad.image_width, ad.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,15 +2,17 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
|
cap.setIndex(0);
|
||||||
// cap.setWH(640, 480);
|
// cap.setWH(640, 480);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
while (1)
|
while (1)
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace sv;
|
using namespace sv;
|
||||||
@@ -14,10 +15,11 @@ int main(int argc, char *argv[])
|
|||||||
cld.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
cld.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(cld.image_width, cld.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -12,10 +13,11 @@ int main(int argc, char *argv[]) {
|
|||||||
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(cod.image_width, cod.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -48,11 +49,12 @@ int main(int argc, char *argv[]) {
|
|||||||
|
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(cod.image_width, cod.image_height);
|
||||||
// cap.setFps(30);
|
// 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类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -12,10 +13,12 @@ int main(int argc, char *argv[]) {
|
|||||||
ed.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
ed.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(ed.image_width, ed.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
|
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,35 +2,17 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include <map>
|
||||||
using namespace std;
|
#include "sv_camera.h"
|
||||||
|
|
||||||
// 定义窗口名称
|
// 定义窗口名称
|
||||||
static const std::string RGB_WINDOW = "Image window";
|
static const std::string RGB_WINDOW = "Image window";
|
||||||
// 框选到的矩形
|
|
||||||
cv::Rect rect_sel;
|
|
||||||
// 框选起始点
|
|
||||||
cv::Point pt_origin;
|
|
||||||
|
|
||||||
// 是否得到一个新的框选区域
|
|
||||||
bool b_renew_ROI = false;
|
|
||||||
// 是否开始跟踪
|
|
||||||
bool b_begin_TRACK = false;
|
|
||||||
// 实现框选逻辑的回调函数
|
// 实现框选逻辑的回调函数
|
||||||
void onMouse(int event, int x, int y, int, void *);
|
void onMouse(int event, int x, int y, int, void *);
|
||||||
|
bool isTarck = false;
|
||||||
struct node
|
bool isStartTarck = false;
|
||||||
{
|
int clickX = -1, clickY = -1;
|
||||||
double x, y;
|
|
||||||
};
|
|
||||||
node p1, p2, p3, p4;
|
|
||||||
node p;
|
|
||||||
double getCross(node p1, node p2, node p)
|
|
||||||
{
|
|
||||||
return (p2.x - p1.x) * (p.y - p1.y) - (p.x - p1.x) * (p2.y - p1.y);
|
|
||||||
}
|
|
||||||
bool b_clicked = false;
|
|
||||||
bool detect_tracking = true;
|
|
||||||
|
|
||||||
// 定义吊舱
|
// 定义吊舱
|
||||||
sv::Gimbal *gimbal;
|
sv::Gimbal *gimbal;
|
||||||
@@ -53,57 +35,125 @@ void gimbalNoTrack(void)
|
|||||||
|
|
||||||
int main(int argc, char *argv[])
|
int main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
|
// 实例化 框选目标跟踪类
|
||||||
|
sv::SingleObjectTracker sot;
|
||||||
|
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
||||||
|
sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
|
||||||
|
|
||||||
|
sv::CommonObjectDetector cod;
|
||||||
|
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
|
||||||
|
|
||||||
// 实例化吊舱
|
// 实例化吊舱
|
||||||
gimbal = new sv::Gimbal(sv::GimbalType::G1, 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作为状态回调函数启用吊舱控制
|
||||||
gimbal->open(GimableCallback);
|
gimbal->open(GimableCallback);
|
||||||
// 定义相机
|
|
||||||
sv::Camera cap;
|
// 打开摄像头
|
||||||
// 设置相机流媒体地址为 192.168.2.64
|
sv::Camera cap(sv::CameraType::G1);
|
||||||
cap.setIp("192.168.2.64");
|
cap.setStream("192.168.2.64",554);
|
||||||
// 设置获取画面分辨率为720P
|
cap.setWH(cod.image_width, cod.image_height);
|
||||||
cap.setWH(1280, 720);
|
|
||||||
// 设置视频帧率为30帧
|
|
||||||
cap.setFps(30);
|
cap.setFps(30);
|
||||||
// 开启相机
|
cap.open(); // CameraID 0
|
||||||
cap.open(sv::CameraType::G1);
|
|
||||||
|
// // 定义相机
|
||||||
|
// 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::namedWindow(RGB_WINDOW);
|
||||||
// 设置窗口操作回调函数,该函数实现整个框选逻辑
|
// 设置窗口操作回调函数,该函数实现整个框选逻辑
|
||||||
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
|
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
|
||||||
// 实例化 框选目标跟踪类
|
|
||||||
sv::SingleObjectTracker sot;
|
|
||||||
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
|
||||||
sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
|
||||||
|
|
||||||
sv::CommonObjectDetector cod;
|
|
||||||
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
|
||||||
|
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
sv::TargetsInFrame lastTgts(frame_id);
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
if (detect_tracking == true)
|
// 如果位标非法 则不能进行任何形式的追踪
|
||||||
|
if (clickX == -1 || clickY == -1)
|
||||||
{
|
{
|
||||||
// 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame
|
isStartTarck = false;
|
||||||
sv::TargetsInFrame tgts(frame_id++);
|
isTarck = false;
|
||||||
// 读取一帧图像到img
|
}
|
||||||
cap.read(img);
|
|
||||||
|
if (isStartTarck && !isTarck)
|
||||||
|
{
|
||||||
|
// 使用上一帧结果初始化追踪器
|
||||||
|
std::map<int, cv::Rect> inBoxList;
|
||||||
|
|
||||||
|
// 计算点击事件是否位于每个目标框内
|
||||||
|
for (int i = 0; i < lastTgts.targets.size(); i++)
|
||||||
|
{
|
||||||
|
int halfWidht = (lastTgts.targets[i].w * lastTgts.width) / 2;
|
||||||
|
int halfHeight = (lastTgts.targets[i].h * lastTgts.height) / 2;
|
||||||
|
int x = lastTgts.targets[i].cx * lastTgts.width;
|
||||||
|
int y = lastTgts.targets[i].cy * lastTgts.height;
|
||||||
|
|
||||||
|
int diffX = x - clickX;
|
||||||
|
int diffY = y - clickY;
|
||||||
|
|
||||||
|
if ((abs(diffX) < halfWidht) && (abs(diffY) < halfHeight))
|
||||||
|
{
|
||||||
|
std::pair<int, cv::Rect> point;
|
||||||
|
point.first = diffX * diffX + diffY * diffY;
|
||||||
|
point.second = cv::Rect(x - halfWidht, y - halfHeight, halfWidht * 2, halfHeight * 2);
|
||||||
|
inBoxList.insert(point);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 取离中心点最近的目标进行跟踪
|
||||||
|
int min = 0X7FFFFFFF;
|
||||||
|
cv::Rect sel;
|
||||||
|
for (auto i = inBoxList.begin(); i != inBoxList.end(); i++)
|
||||||
|
{
|
||||||
|
if (i->first < min)
|
||||||
|
{
|
||||||
|
min = i->first;
|
||||||
|
sel = i->second;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// min被赋值则存在一个目标框与点击的点重合
|
||||||
|
if (min != 0X7FFFFFFF)
|
||||||
|
{
|
||||||
|
sot.init(img, sel);
|
||||||
|
isTarck = true;
|
||||||
|
printf("rect_sel Yes\n");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
isTarck = false;
|
||||||
|
printf("rect_sel No\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
isStartTarck = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
sv::TargetsInFrame tgts(frame_id++);
|
||||||
|
// 读取一帧图像
|
||||||
|
cap.read(img);
|
||||||
|
|
||||||
|
if (!isTarck)
|
||||||
|
{
|
||||||
|
// 缩放图像尺寸用于适配检测器
|
||||||
cv::resize(img, img, cv::Size(cod.image_width, cod.image_height));
|
cv::resize(img, img, cv::Size(cod.image_width, cod.image_height));
|
||||||
|
|
||||||
// 执行通用目标检测
|
// 进行通用目标检测
|
||||||
cod.detect(img, tgts);
|
cod.detect(img, tgts);
|
||||||
|
|
||||||
gimbalNoTrack();
|
gimbalNoTrack();
|
||||||
|
|
||||||
// 可视化检测结果,叠加到img上
|
// 向控制台输出检测结果
|
||||||
sv::drawTargetsInFrame(img, tgts);
|
|
||||||
|
|
||||||
// 控制台打印通用目标检测结果
|
|
||||||
printf("Frame-[%d]\n", frame_id);
|
printf("Frame-[%d]\n", frame_id);
|
||||||
// 打印当前检测的FPS
|
// 打印当前检测的FPS
|
||||||
printf(" FPS = %.2f\n", tgts.fps);
|
printf(" FPS = %.2f\n", tgts.fps);
|
||||||
@@ -124,109 +174,78 @@ int main(int argc, char *argv[])
|
|||||||
printf(" Object Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[i].los_ax, tgts.targets[i].los_ay);
|
printf(" Object Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[i].los_ax, tgts.targets[i].los_ay);
|
||||||
// 打印每个目标的3D位置(在相机坐标系下),跟目标实际长宽、相机参数相关
|
// 打印每个目标的3D位置(在相机坐标系下),跟目标实际长宽、相机参数相关
|
||||||
printf(" Object Position = (x, y, z) = (%.3f, %.3f, %.3f)\n", tgts.targets[i].px, tgts.targets[i].py, tgts.targets[i].pz);
|
printf(" Object Position = (x, y, z) = (%.3f, %.3f, %.3f)\n", tgts.targets[i].px, tgts.targets[i].py, tgts.targets[i].pz);
|
||||||
p1.x = tgts.targets[i].cx * tgts.width - tgts.targets[i].w * tgts.width / 2;
|
|
||||||
p1.y = tgts.targets[i].cy * tgts.height - tgts.targets[i].h * tgts.height / 2;
|
|
||||||
p2.x = tgts.targets[i].cx * tgts.width + tgts.targets[i].w * tgts.width / 2;
|
|
||||||
p2.y = tgts.targets[i].cy * tgts.height - tgts.targets[i].h * tgts.height / 2;
|
|
||||||
p4.x = tgts.targets[i].cx * tgts.width - tgts.targets[i].w * tgts.width / 2;
|
|
||||||
p4.y = tgts.targets[i].cy * tgts.height + tgts.targets[i].h * tgts.height / 2;
|
|
||||||
p3.x = tgts.targets[i].cx * tgts.width + tgts.targets[i].w * tgts.width / 2;
|
|
||||||
p3.y = tgts.targets[i].cy * tgts.height + tgts.targets[i].h * tgts.height / 2;
|
|
||||||
p.x = pt_origin.x;
|
|
||||||
p.y = pt_origin.y;
|
|
||||||
std::cout << "p.x " << p.x << "\t"
|
|
||||||
<< "p.y " << p.y << std::endl;
|
|
||||||
if (getCross(p1, p2, p) * getCross(p3, p4, p) >= 0 && getCross(p2, p3, p) * getCross(p4, p1, p) >= 0)
|
|
||||||
{
|
|
||||||
b_begin_TRACK = false;
|
|
||||||
detect_tracking = false;
|
|
||||||
// pt_origin = cv::Point(nor_x, nor_p_y);
|
|
||||||
// std::cout << "pt_origin " <<nor_x<<"/t"<<nor_p_y<< std::endl;
|
|
||||||
rect_sel = cv::Rect(p1.x, p1.y, tgts.targets[i].w * tgts.width, tgts.targets[i].h * tgts.height);
|
|
||||||
// std::cout << rect_sel << std::endl;
|
|
||||||
b_renew_ROI = true;
|
|
||||||
frame_id = 0;
|
|
||||||
printf("rect_sel Yes\n");
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
printf("rect_sel No\n");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
// 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame
|
// 缩放图像尺寸用于适配追踪器
|
||||||
sv::TargetsInFrame tgts(frame_id++);
|
|
||||||
// 读取一帧图像到img
|
|
||||||
cap.read(img);
|
|
||||||
cv::resize(img, img, cv::Size(sot.image_width, sot.image_height));
|
cv::resize(img, img, cv::Size(sot.image_width, sot.image_height));
|
||||||
// 开始 单目标跟踪 逻辑
|
|
||||||
// 是否有新的目标被手动框选
|
|
||||||
if (b_renew_ROI)
|
|
||||||
{
|
|
||||||
// 拿新的框选区域 来 初始化跟踪器
|
|
||||||
sot.init(img, rect_sel);
|
|
||||||
// std::cout << rect_sel << std::endl;
|
|
||||||
// 重置框选标志
|
|
||||||
b_renew_ROI = false;
|
|
||||||
// 开始跟踪
|
|
||||||
b_begin_TRACK = true;
|
|
||||||
}
|
|
||||||
else if (b_begin_TRACK)
|
|
||||||
{
|
|
||||||
// 以前一帧的结果继续跟踪
|
|
||||||
sot.track(img, tgts);
|
|
||||||
gimbalTrack(tgts.targets[0].cx - 0.5f, tgts.targets[0].cy - 0.5f);
|
|
||||||
|
|
||||||
// 可视化检测结果,叠加到img上
|
// 图像追踪
|
||||||
sv::drawTargetsInFrame(img, tgts);
|
sot.track(img, tgts);
|
||||||
// 控制台打印 单目标跟踪 结果
|
|
||||||
|
// 吊舱追踪
|
||||||
|
gimbalTrack(tgts.targets[0].cx - 0.5f, tgts.targets[0].cy - 0.5f);
|
||||||
|
|
||||||
|
// 向控制台输出追踪结果
|
||||||
|
printf("Frame-[%d]\n", frame_id);
|
||||||
|
// 打印当前检测的FPS
|
||||||
|
printf(" FPS = %.2f\n", tgts.fps);
|
||||||
|
// 打印当前相机的视场角(degree)
|
||||||
|
printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y);
|
||||||
|
if (tgts.targets.size() > 0)
|
||||||
|
{
|
||||||
printf("Frame-[%d]\n", frame_id);
|
printf("Frame-[%d]\n", frame_id);
|
||||||
// 打印当前检测的FPS
|
// 打印 跟踪目标 的中心位置,cx,cy的值域为[0, 1]
|
||||||
printf(" FPS = %.2f\n", tgts.fps);
|
printf(" Tracking Center (cx, cy) = (%.3f, %.3f)\n", tgts.targets[0].cx, tgts.targets[0].cy);
|
||||||
// 打印当前相机的视场角(degree)
|
// 打印 跟踪目标 的外接矩形框的宽度、高度,w,h的值域为(0, 1]
|
||||||
printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y);
|
printf(" Tracking Size (w, h) = (%.3f, %.3f)\n", tgts.targets[0].w, tgts.targets[0].h);
|
||||||
if (tgts.targets.size() > 0)
|
// 打印 跟踪目标 的视线角,跟相机视场相关
|
||||||
{
|
printf(" Tracking Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[0].los_ax, tgts.targets[0].los_ay);
|
||||||
printf("Frame-[%d]\n", frame_id);
|
|
||||||
// 打印 跟踪目标 的中心位置,cx,cy的值域为[0, 1]
|
|
||||||
printf(" Tracking Center (cx, cy) = (%.3f, %.3f)\n", tgts.targets[0].cx, tgts.targets[0].cy);
|
|
||||||
// 打印 跟踪目标 的外接矩形框的宽度、高度,w,h的值域为(0, 1]
|
|
||||||
printf(" Tracking Size (w, h) = (%.3f, %.3f)\n", tgts.targets[0].w, tgts.targets[0].h);
|
|
||||||
// 打印 跟踪目标 的视线角,跟相机视场相关
|
|
||||||
printf(" Tracking Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[0].los_ax, tgts.targets[0].los_ay);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
} // end of tracking
|
}
|
||||||
|
|
||||||
|
// 叠加目标框至原始图像
|
||||||
|
sv::drawTargetsInFrame(img, tgts);
|
||||||
// 显示检测结果img
|
// 显示检测结果img
|
||||||
cv::imshow(RGB_WINDOW, img);
|
cv::imshow(RGB_WINDOW, img);
|
||||||
cv::waitKey(10);
|
cv::waitKey(10);
|
||||||
|
|
||||||
|
lastTgts = tgts;
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void onMouse(int event, int x, int y, int, void *)
|
void onMouse(int event, int x, int y, int, void *)
|
||||||
{
|
{
|
||||||
if (b_clicked)
|
// 左键点击 进入追踪模式
|
||||||
|
if (event == cv::MouseEventTypes::EVENT_LBUTTONDOWN)
|
||||||
{
|
{
|
||||||
// 更新框选区域坐标
|
if (!isTarck && !isStartTarck)
|
||||||
pt_origin.x = 0;
|
{
|
||||||
pt_origin.y = 0;
|
clickX = x;
|
||||||
|
clickY = y;
|
||||||
|
isStartTarck = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
// 左键按下
|
// 右键点击 退出追踪模式
|
||||||
if (event == cv::EVENT_LBUTTONDOWN)
|
else if (event == cv::MouseEventTypes::EVENT_RBUTTONDOWN)
|
||||||
{
|
{
|
||||||
detect_tracking = true;
|
if (isTarck)
|
||||||
pt_origin = cv::Point(x, y);
|
{
|
||||||
|
clickX = -1;
|
||||||
|
clickY = -1;
|
||||||
|
isTarck = false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
// 中键点击 归中(仅非追踪模式下有效)
|
||||||
else if (event == cv::EVENT_RBUTTONDOWN)
|
else if (event == cv::MouseEventTypes::EVENT_MBUTTONDOWN)
|
||||||
{
|
{
|
||||||
detect_tracking = true;
|
if (!isTarck)
|
||||||
b_renew_ROI = false;
|
{
|
||||||
b_begin_TRACK = false;
|
gimbal->setHome();
|
||||||
b_clicked = true;
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -3,6 +3,7 @@
|
|||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
// #include "gimbal_tools.hpp"
|
// #include "gimbal_tools.hpp"
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -33,32 +34,40 @@ void gimbalNoTrack(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
int main(int argc, char *argv[])
|
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);
|
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
|
||||||
// 使用 /dev/ttyUSB0 作为控制串口
|
// 使用 /dev/ttyUSB0 作为控制串口
|
||||||
gimbal->setSerialPort("/dev/ttyUSB0");
|
gimbal->setSerialPort("/dev/ttyUSB0");
|
||||||
// 以GimableCallback作为状态回调函数启用吊舱控制
|
// 以GimableCallback作为状态回调函数启用吊舱控制
|
||||||
gimbal->open(GimableCallback);
|
gimbal->open(GimableCallback);
|
||||||
// 定义相机
|
|
||||||
sv::Camera cap;
|
// 打开摄像头
|
||||||
// 设置相机流媒体地址为 192.168.2.64
|
sv::Camera cap(sv::CameraType::G1);
|
||||||
cap.setIp("192.168.2.64");
|
cap.setStream("192.168.2.64", 554);
|
||||||
// 设置获取画面分辨率为720P
|
cap.setWH(lmd.image_width, lmd.image_height);
|
||||||
cap.setWH(1280, 720);
|
|
||||||
// 设置视频帧率为30帧
|
|
||||||
cap.setFps(30);
|
cap.setFps(30);
|
||||||
// 开启相机
|
cap.open(); // CameraID 0
|
||||||
cap.open(sv::CameraType::G1);
|
|
||||||
|
// // 定义相机
|
||||||
|
// 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::namedWindow(RGB_WINDOW);
|
||||||
// 设置窗口操作回调函数,该函数实现吊舱控制
|
// 设置窗口操作回调函数,该函数实现吊舱控制
|
||||||
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
|
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
|
||||||
// 实例化 圆形降落标志 检测器类
|
|
||||||
sv::LandingMarkerDetector lmd;
|
|
||||||
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
|
||||||
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
|
|
||||||
|
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
|
|||||||
@@ -2,13 +2,14 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
// yaw roll pitch
|
// yaw roll pitch
|
||||||
double gimbalEulerAngle[3];
|
double gimbalEulerAngle[3];
|
||||||
void gimableCallback(double &imu_ang_r, double &imu_ang_p, double &imu_ang_y,
|
void gimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang_y,
|
||||||
double &frame_ang_r, double &frame_ang_p, double &frame_ang_y,
|
double &imu_ang_r, double &imu_ang_p, double &imu_ang_y,
|
||||||
double &fov_x, double &fov_y)
|
double &fov_x, double &fov_y)
|
||||||
{
|
{
|
||||||
static int count = 0;
|
static int count = 0;
|
||||||
@@ -42,32 +43,41 @@ static const std::string RGB_WINDOW = "Image window";
|
|||||||
void onMouse(int event, int x, int y, int, void *);
|
void onMouse(int event, int x, int y, int, void *);
|
||||||
|
|
||||||
int main(int argc, char *argv[])
|
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);
|
gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL);
|
||||||
// 使用 /dev/ttyUSB0 作为控制串口
|
// 使用 /dev/ttyUSB0 作为控制串口
|
||||||
gimbal->setSerialPort("/dev/ttyUSB0");
|
gimbal->setSerialPort("/dev/ttyUSB0");
|
||||||
// 以gimableCallback作为状态回调函数启用吊舱控制
|
// 以gimableCallback作为状态回调函数启用吊舱控制
|
||||||
gimbal->open(gimableCallback);
|
gimbal->open(gimableCallback);
|
||||||
// 定义相机
|
|
||||||
sv::Camera cap;
|
// 打开摄像头
|
||||||
// 设置相机流媒体地址为 192.168.2.64
|
sv::Camera cap(sv::CameraType::G1);
|
||||||
cap.setIp("192.168.2.64");
|
cap.setStream("192.168.2.64",554);
|
||||||
// 设置获取画面分辨率为720P
|
cap.setWH(ad.image_width, ad.image_height);
|
||||||
cap.setWH(1280, 720);
|
|
||||||
// 设置视频帧率为30帧
|
|
||||||
cap.setFps(30);
|
cap.setFps(30);
|
||||||
// 开启相机
|
cap.open(); // CameraID 0
|
||||||
cap.open(sv::CameraType::G1);
|
|
||||||
|
// // 定义相机
|
||||||
|
// 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::namedWindow(RGB_WINDOW);
|
||||||
// 设置窗口操作回调函数,该函数实现吊舱控制
|
// 设置窗口操作回调函数,该函数实现吊舱控制
|
||||||
cv::setMouseCallback(RGB_WINDOW, onMouse, 0);
|
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;
|
sv::UDPServer udp;
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
@@ -80,6 +90,8 @@ int main(int argc, char *argv[])
|
|||||||
// 读取一帧图像到img
|
// 读取一帧图像到img
|
||||||
cap.read(img);
|
cap.read(img);
|
||||||
|
|
||||||
|
// std::cout << img.type() << std::endl;
|
||||||
|
|
||||||
// 执行Aruco二维码检测
|
// 执行Aruco二维码检测
|
||||||
ad.detect(img, tgts);
|
ad.detect(img, tgts);
|
||||||
|
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
@@ -11,11 +11,13 @@ int main(int argc, char *argv[]) {
|
|||||||
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
||||||
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(lmd.image_width, lmd.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
|
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@@ -15,11 +16,13 @@ int main(int argc, char *argv[]) {
|
|||||||
mot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
mot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
mot.init(&cod);
|
mot.init(&cod);
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(cod.image_width, cod.image_height);
|
||||||
// cap.setFps(30);
|
// cap.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
|
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
using namespace std;
|
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_1280x720.yaml");
|
||||||
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1920x1080.yaml");
|
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1920x1080.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
|
cap.setWH(sot.image_width, sot.image_height);
|
||||||
// cap.setFps(30);
|
// 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");
|
// cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4");
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
|
|||||||
140
samples/demo/udp_detection_info_receiver_by_airborne.cpp
Normal file
140
samples/demo/udp_detection_info_receiver_by_airborne.cpp
Normal file
@@ -0,0 +1,140 @@
|
|||||||
|
#include <iostream>
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
#include <netinet/in.h>
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#define PORT 12346 // UDP端口号
|
||||||
|
|
||||||
|
// 枚举定义消息类型
|
||||||
|
enum MessageType {
|
||||||
|
TIMESTAMP = 0x00,
|
||||||
|
CLICK_COORDINATES = 0x01,
|
||||||
|
TARGET_BOX_COORDINATES = 0x02,
|
||||||
|
CLICK_COORDINATES_FRAME_ID = 0x03,
|
||||||
|
TARGET_BOX_COORDINATES_FRAME_ID = 0x04
|
||||||
|
};
|
||||||
|
|
||||||
|
// 定义消息结构体
|
||||||
|
#pragma pack(1) // 使用1字节对齐方式
|
||||||
|
struct Message {
|
||||||
|
unsigned char header[2]; // 帧头
|
||||||
|
unsigned char type; // 消息类型
|
||||||
|
unsigned char reserved; // 保留字段
|
||||||
|
unsigned int requestID; // 请求ID
|
||||||
|
unsigned int dataLength; // 数据长度
|
||||||
|
unsigned char* data; // 数据段
|
||||||
|
};
|
||||||
|
#pragma pack() // 恢复默认对齐方式
|
||||||
|
|
||||||
|
// 解析时间戳消息
|
||||||
|
void parseTimestampMessage(unsigned char* data) {
|
||||||
|
unsigned short year = ntohs(*reinterpret_cast<unsigned short*>(data));
|
||||||
|
unsigned char month = *(data + 2);
|
||||||
|
unsigned char day = *(data + 3);
|
||||||
|
unsigned char hour = *(data + 4);
|
||||||
|
unsigned char minute = *(data + 5);
|
||||||
|
unsigned char second = *(data + 6);
|
||||||
|
unsigned short millisecond = ntohs(*reinterpret_cast<unsigned short*>(data + 7));
|
||||||
|
|
||||||
|
std::cout << "Timestamp: " << static_cast<int>(year) << "-" << static_cast<int>(month)
|
||||||
|
<< "-" << static_cast<int>(day) << " " << static_cast<int>(hour) << ":"
|
||||||
|
<< static_cast<int>(minute) << ":" << static_cast<int>(second) << "."
|
||||||
|
<< static_cast<int>(millisecond) << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 解析点击坐标消息
|
||||||
|
void parseClickCoordinatesMessage(unsigned char* data) {
|
||||||
|
float x = *reinterpret_cast<float*>(data);
|
||||||
|
float y = *reinterpret_cast<float*>(data + 4);
|
||||||
|
|
||||||
|
std::cout << "Click coordinates: (" << x << ", " << y << ")" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 解析目标框坐标消息
|
||||||
|
void parseTargetBoxCoordinatesMessage(unsigned char* data) {
|
||||||
|
float x1 = *reinterpret_cast<float*>(data);
|
||||||
|
float y1 = *reinterpret_cast<float*>(data + 4);
|
||||||
|
float x2 = *reinterpret_cast<float*>(data + 8);
|
||||||
|
float y2 = *reinterpret_cast<float*>(data + 12);
|
||||||
|
|
||||||
|
std::cout << "Target box coordinates: (" << x1 << ", " << y1 << ") - ("
|
||||||
|
<< x2 << ", " << y2 << ")" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 解析UDP数据包
|
||||||
|
void parseUDPData(unsigned char* buffer, int length) {
|
||||||
|
if (length < 13) {
|
||||||
|
std::cout << "Invalid UDP data format" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
Message message;
|
||||||
|
memcpy(&message, buffer, sizeof(Message));
|
||||||
|
|
||||||
|
// 解析消息类型
|
||||||
|
MessageType messageType = static_cast<MessageType>(message.type);
|
||||||
|
|
||||||
|
// 根据消息类型处理数据
|
||||||
|
switch (messageType) {
|
||||||
|
case TIMESTAMP:
|
||||||
|
if (length != 9) {
|
||||||
|
std::cout << "Invalid timestamp message length" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
parseTimestampMessage(message.data);
|
||||||
|
break;
|
||||||
|
case CLICK_COORDINATES:
|
||||||
|
if (length != 13) {
|
||||||
|
std::cout << "Invalid click coordinates message length" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
parseClickCoordinatesMessage(message.data);
|
||||||
|
break;
|
||||||
|
case TARGET_BOX_COORDINATES:
|
||||||
|
if (length != 21) {
|
||||||
|
std::cout << "Invalid target box coordinates message length" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
parseTargetBoxCoordinatesMessage(message.data);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
std::cout << "Unsupported message type" << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
int sockfd;
|
||||||
|
struct sockaddr_in servaddr, cliaddr;
|
||||||
|
unsigned char buffer[4096];
|
||||||
|
|
||||||
|
// 创建UDP套接字
|
||||||
|
sockfd = socket(AF_INET, SOCK_DGRAM, 0);
|
||||||
|
|
||||||
|
memset(&servaddr, 0, sizeof(servaddr));
|
||||||
|
memset(&cliaddr, 0, sizeof(cliaddr));
|
||||||
|
|
||||||
|
servaddr.sin_family = AF_INET;
|
||||||
|
servaddr.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||||
|
servaddr.sin_port = htons(PORT);
|
||||||
|
|
||||||
|
// 绑定UDP套接字到端口
|
||||||
|
bind(sockfd, (const struct sockaddr*)&servaddr, sizeof(servaddr));
|
||||||
|
|
||||||
|
while (true) {
|
||||||
|
socklen_t len = sizeof(cliaddr);
|
||||||
|
|
||||||
|
// 接收UDP数据包
|
||||||
|
ssize_t n = recvfrom(sockfd, buffer, sizeof(buffer), MSG_WAITALL,
|
||||||
|
(struct sockaddr*)&cliaddr, &len);
|
||||||
|
|
||||||
|
// 解析UDP数据包
|
||||||
|
parseUDPData(buffer, n);
|
||||||
|
}
|
||||||
|
|
||||||
|
close(sockfd);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
@@ -2,7 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
@@ -11,11 +11,12 @@ int main(int argc, char *argv[]) {
|
|||||||
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
||||||
ad.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
|
ad.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
cap.setWH(640, 480);
|
cap.setIndex(0);
|
||||||
cap.setFps(30);
|
cap.setWH(ad.image_width, ad.image_height);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
// cap.setFps(30);
|
||||||
|
cap.open(); // CameraID 0
|
||||||
|
|
||||||
sv::UDPServer udp;
|
sv::UDPServer udp;
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
|
|||||||
@@ -2,44 +2,89 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
struct node
|
||||||
// 打开摄像头
|
{
|
||||||
|
double x, y;
|
||||||
|
};
|
||||||
|
|
||||||
|
node p1;
|
||||||
|
|
||||||
|
// 框选到的矩形
|
||||||
|
cv::Rect rect_sel;
|
||||||
|
|
||||||
|
int main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
// 实例化 框选目标跟踪类
|
||||||
sv::VeriDetector veri;
|
sv::VeriDetector veri;
|
||||||
|
// 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件
|
||||||
veri.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
veri.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
|
|
||||||
cv::VideoCapture cap1("/home/amov/Videos/com/FlyVideo_2023-09-02_11-36-00.avi");
|
sv::CommonObjectDetector cod;
|
||||||
cv::VideoCapture cap2("/home/amov/Videos/com/FlyVideo_2023-09-02_11-41-55.avi");
|
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
|
||||||
// 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.setFps(30);
|
||||||
//cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
|
cv::Mat img;
|
||||||
|
|
||||||
cv::Mat img1,img2;
|
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
|
|
||||||
// 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame
|
// 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame
|
||||||
sv::TargetsInFrame tgts(frame_id++);
|
sv::TargetsInFrame tgts(frame_id++);
|
||||||
|
|
||||||
// 读取一帧图像到img
|
// 读取一帧图像到img
|
||||||
cap1.read(img1);
|
cap.read(img);
|
||||||
cap2.read(img2);
|
cv::resize(img, img, cv::Size(cod.image_width, cod.image_height));
|
||||||
|
|
||||||
cv::resize(img1, img1, cv::Size(224, 224));
|
// 执行通用目标检测
|
||||||
cv::resize(img2, img2, cv::Size(224, 224));
|
cod.detect(img, tgts);
|
||||||
|
|
||||||
veri.detect(img1, img2, tgts);
|
// 可视化检测结果,叠加到img上
|
||||||
|
sv::drawTargetsInFrame(img, tgts);
|
||||||
|
|
||||||
|
// 控制台打印通用目标检测结果
|
||||||
|
printf("Frame-[%d]\n", frame_id);
|
||||||
|
// 打印当前检测的FPS
|
||||||
|
printf(" FPS = %.2f\n", tgts.fps);
|
||||||
|
// 打印当前相机的视场角(degree)
|
||||||
|
printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y);
|
||||||
|
for (int i = 0; i < tgts.targets.size(); i++)
|
||||||
|
{
|
||||||
|
printf("Frame-[%d], Object-[%d]\n", frame_id, i);
|
||||||
|
// 打印每个目标的中心位置,cx,cy的值域为[0, 1]
|
||||||
|
printf(" Object Center (cx, cy) = (%.3f, %.3f)\n", tgts.targets[i].cx, tgts.targets[i].cy);
|
||||||
|
// 打印每个目标的外接矩形框的宽度、高度,w,h的值域为(0, 1]
|
||||||
|
printf(" Object Size (w, h) = (%.3f, %.3f)\n", tgts.targets[i].w, tgts.targets[i].h);
|
||||||
|
// 打印每个目标的置信度
|
||||||
|
printf(" Object Score = %.3f\n", tgts.targets[i].score);
|
||||||
|
// 打印每个目标的类别,字符串类型
|
||||||
|
printf(" Object Category = %s, Category ID = [%d]\n", tgts.targets[i].category.c_str(), tgts.targets[i].category_id);
|
||||||
|
// 打印每个目标的视线角,跟相机视场相关
|
||||||
|
printf(" Object Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[i].los_ax, tgts.targets[i].los_ay);
|
||||||
|
// 打印每个目标的3D位置(在相机坐标系下),跟目标实际长宽、相机参数相关
|
||||||
|
printf(" Object Position = (x, y, z) = (%.3f, %.3f, %.3f)\n", tgts.targets[i].px, tgts.targets[i].py, tgts.targets[i].pz);
|
||||||
|
|
||||||
// 显示img
|
if (tgts.targets[i].category_id == 2)
|
||||||
// cv::imshow("img", img);
|
{
|
||||||
// cv::waitKey(10);
|
p1.x = tgts.targets[i].cx * tgts.width - tgts.targets[i].w * tgts.width / 2;
|
||||||
|
p1.y = tgts.targets[i].cy * tgts.height - tgts.targets[i].h * tgts.height / 2;
|
||||||
|
rect_sel = cv::Rect(p1.x, p1.y, tgts.targets[i].w * tgts.width, tgts.targets[i].h * tgts.height);
|
||||||
|
veri.detect(img, rect_sel, tgts.targets[i]);
|
||||||
|
// 打印每个目标的CosineSimilarity
|
||||||
|
printf(" CosineSimilarity Score = %.3f\n", tgts.targets[i].sim_score);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 显示检测结果img
|
||||||
|
cv::imshow("img", img);
|
||||||
|
cv::waitKey(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
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");
|
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.setFps(30);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.open(); // CameraID 0
|
||||||
// 实例化OpenCV的Mat类,用于内存单帧图像
|
// 实例化OpenCV的Mat类,用于内存单帧图像
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
int frame_id = 0;
|
int frame_id = 0;
|
||||||
|
|||||||
@@ -2,15 +2,17 @@
|
|||||||
#include <string>
|
#include <string>
|
||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
// 打开摄像头
|
// 打开摄像头
|
||||||
sv::Camera cap;
|
sv::Camera cap(sv::CameraType::WEBCAM);
|
||||||
// cap.setWH(1280, 720);
|
cap.setIndex(0);
|
||||||
// cap.setFps(30);
|
cap.setWH(1280, 720);
|
||||||
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
|
cap.setFps(30);
|
||||||
|
cap.open(); // CameraID 0
|
||||||
|
|
||||||
// 实例化视频推流类sv::VideoStreamer
|
// 实例化视频推流类sv::VideoStreamer
|
||||||
sv::VideoStreamer streamer;
|
sv::VideoStreamer streamer;
|
||||||
|
|||||||
@@ -3,6 +3,7 @@
|
|||||||
// 包含SpireCV SDK头文件
|
// 包含SpireCV SDK头文件
|
||||||
#include <sv_world.h>
|
#include <sv_world.h>
|
||||||
#include <chrono>
|
#include <chrono>
|
||||||
|
#include "sv_camera.h"
|
||||||
|
|
||||||
// yaw roll pitch
|
// yaw roll pitch
|
||||||
double gimbalEulerAngle[3];
|
double gimbalEulerAngle[3];
|
||||||
@@ -143,14 +144,20 @@ int main(int argc, char *argv[])
|
|||||||
std::cout << " pass... " << std::endl;
|
std::cout << " pass... " << std::endl;
|
||||||
std::cout << " start image test " << 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.setWH(1280, 720);
|
||||||
cap.setFps(30);
|
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;
|
std::cout << " gimbal image error , failed !!!!!" << std::endl;
|
||||||
return -1;
|
return -1;
|
||||||
|
|||||||
@@ -28,6 +28,10 @@ sudo apt install -y libjasper1 libjasper-dev
|
|||||||
|
|
||||||
sudo apt install -y python3-dev python3-numpy libtbb2 libtbb-dev libjpeg-dev libpng-dev libtiff-dev
|
sudo apt install -y python3-dev python3-numpy libtbb2 libtbb-dev libjpeg-dev libpng-dev libtiff-dev
|
||||||
sudo apt install -y libdc1394-22-dev
|
sudo apt install -y libdc1394-22-dev
|
||||||
|
sudo apt install -y libcurl4 build-essential pkg-config cmake libopenblas-dev libeigen3-dev \
|
||||||
|
libtbb-dev libavcodec-dev libavformat-dev libgstreamer-plugins-base1.0-dev \
|
||||||
|
libgstreamer1.0-dev libswscale-dev libgtk-3-dev libpng-dev libjpeg-dev \
|
||||||
|
libcanberra-gtk-module libcanberra-gtk3-module
|
||||||
|
|
||||||
|
|
||||||
echo "\033[32m[INFO]:\033[0m unzip opencv-4.7.0.zip ..."
|
echo "\033[32m[INFO]:\033[0m unzip opencv-4.7.0.zip ..."
|
||||||
|
|||||||
106
video_io/driver/sv_camera_G1.cpp
Normal file
106
video_io/driver/sv_camera_G1.cpp
Normal 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;
|
||||||
|
}
|
||||||
85
video_io/driver/sv_camera_GX40.cpp
Normal file
85
video_io/driver/sv_camera_GX40.cpp
Normal 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;
|
||||||
|
}
|
||||||
78
video_io/driver/sv_camera_MC1.cpp
Normal file
78
video_io/driver/sv_camera_MC1.cpp
Normal 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;
|
||||||
|
}
|
||||||
149
video_io/driver/sv_camera_V4L2s.cpp
Normal file
149
video_io/driver/sv_camera_V4L2s.cpp
Normal 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)
|
||||||
|
{
|
||||||
|
}
|
||||||
79
video_io/driver/sv_camera_file.cpp
Normal file
79
video_io/driver/sv_camera_file.cpp
Normal 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;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
95
video_io/driver/sv_camera_mipi.cpp
Normal file
95
video_io/driver/sv_camera_mipi.cpp
Normal 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;
|
||||||
|
}
|
||||||
74
video_io/driver/sv_camera_streaming.cpp
Normal file
74
video_io/driver/sv_camera_streaming.cpp
Normal 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
192
video_io/sv_camera.cpp
Normal 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
138
video_io/sv_camera_def.cpp
Normal 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();
|
||||||
|
}
|
||||||
|
}
|
||||||
83
video_io/sv_camera_privately.h
Normal file
83
video_io/sv_camera_privately.h
Normal 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
|
||||||
@@ -969,172 +969,172 @@ void VideoWriterBase::releaseImpl()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
CameraBase::CameraBase(CameraType type, int id)
|
// CameraBase::CameraBase(CameraType type, int id)
|
||||||
{
|
// {
|
||||||
this->_is_running = false;
|
// this->_is_running = false;
|
||||||
this->_is_updated = false;
|
// this->_is_updated = false;
|
||||||
this->_type = type;
|
// this->_type = type;
|
||||||
|
|
||||||
this->_width = -1;
|
// this->_width = -1;
|
||||||
this->_height = -1;
|
// this->_height = -1;
|
||||||
this->_fps = -1;
|
// this->_fps = -1;
|
||||||
this->_ip = "192.168.2.64";
|
// this->_ip = "192.168.2.64";
|
||||||
this->_port = -1;
|
// this->_port = -1;
|
||||||
this->_brightness = -1;
|
// this->_brightness = -1;
|
||||||
this->_contrast = -1;
|
// this->_contrast = -1;
|
||||||
this->_saturation = -1;
|
// this->_saturation = -1;
|
||||||
this->_hue = -1;
|
// this->_hue = -1;
|
||||||
this->_exposure = -1;
|
// this->_exposure = -1;
|
||||||
|
|
||||||
this->open(type, id);
|
// this->open(type, id);
|
||||||
}
|
// }
|
||||||
CameraBase::~CameraBase()
|
// CameraBase::~CameraBase()
|
||||||
{
|
// {
|
||||||
this->_is_running = false;
|
// this->_is_running = false;
|
||||||
// this->_tt.join();
|
// // this->_tt.join();
|
||||||
}
|
// }
|
||||||
void CameraBase::setWH(int width, int height)
|
// void CameraBase::setWH(int width, int height)
|
||||||
{
|
// {
|
||||||
this->_width = width;
|
// this->_width = width;
|
||||||
this->_height = height;
|
// this->_height = height;
|
||||||
}
|
// }
|
||||||
void CameraBase::setFps(int fps)
|
// void CameraBase::setFps(int fps)
|
||||||
{
|
// {
|
||||||
this->_fps = fps;
|
// this->_fps = fps;
|
||||||
}
|
// }
|
||||||
void CameraBase::setIp(std::string ip)
|
// void CameraBase::setIp(std::string ip)
|
||||||
{
|
// {
|
||||||
this->_ip = ip;
|
// this->_ip = ip;
|
||||||
}
|
// }
|
||||||
void CameraBase::setPort(int port)
|
// void CameraBase::setPort(int port)
|
||||||
{
|
// {
|
||||||
this->_port = port;
|
// this->_port = port;
|
||||||
}
|
// }
|
||||||
void CameraBase::setBrightness(double brightness)
|
// void CameraBase::setBrightness(double brightness)
|
||||||
{
|
// {
|
||||||
this->_brightness = brightness;
|
// this->_brightness = brightness;
|
||||||
}
|
// }
|
||||||
void CameraBase::setContrast(double contrast)
|
// void CameraBase::setContrast(double contrast)
|
||||||
{
|
// {
|
||||||
this->_contrast = contrast;
|
// this->_contrast = contrast;
|
||||||
}
|
// }
|
||||||
void CameraBase::setSaturation(double saturation)
|
// void CameraBase::setSaturation(double saturation)
|
||||||
{
|
// {
|
||||||
this->_saturation = saturation;
|
// this->_saturation = saturation;
|
||||||
}
|
// }
|
||||||
void CameraBase::setHue(double hue)
|
// void CameraBase::setHue(double hue)
|
||||||
{
|
// {
|
||||||
this->_hue = hue;
|
// this->_hue = hue;
|
||||||
}
|
// }
|
||||||
void CameraBase::setExposure(double exposure)
|
// void CameraBase::setExposure(double exposure)
|
||||||
{
|
// {
|
||||||
this->_exposure = exposure;
|
// this->_exposure = exposure;
|
||||||
}
|
// }
|
||||||
|
|
||||||
int CameraBase::getW()
|
// int CameraBase::getW()
|
||||||
{
|
// {
|
||||||
return this->_width;
|
// return this->_width;
|
||||||
}
|
// }
|
||||||
int CameraBase::getH()
|
// int CameraBase::getH()
|
||||||
{
|
// {
|
||||||
return this->_height;
|
// return this->_height;
|
||||||
}
|
// }
|
||||||
int CameraBase::getFps()
|
// int CameraBase::getFps()
|
||||||
{
|
// {
|
||||||
return this->_fps;
|
// return this->_fps;
|
||||||
}
|
// }
|
||||||
std::string CameraBase::getIp()
|
// std::string CameraBase::getIp()
|
||||||
{
|
// {
|
||||||
return this->_ip;
|
// return this->_ip;
|
||||||
}
|
// }
|
||||||
int CameraBase::getPort()
|
// int CameraBase::getPort()
|
||||||
{
|
// {
|
||||||
return this->_port;
|
// return this->_port;
|
||||||
}
|
// }
|
||||||
double CameraBase::getBrightness()
|
// double CameraBase::getBrightness()
|
||||||
{
|
// {
|
||||||
return this->_brightness;
|
// return this->_brightness;
|
||||||
}
|
// }
|
||||||
double CameraBase::getContrast()
|
// double CameraBase::getContrast()
|
||||||
{
|
// {
|
||||||
return this->_contrast;
|
// return this->_contrast;
|
||||||
}
|
// }
|
||||||
double CameraBase::getSaturation()
|
// double CameraBase::getSaturation()
|
||||||
{
|
// {
|
||||||
return this->_saturation;
|
// return this->_saturation;
|
||||||
}
|
// }
|
||||||
double CameraBase::getHue()
|
// double CameraBase::getHue()
|
||||||
{
|
// {
|
||||||
return this->_hue;
|
// return this->_hue;
|
||||||
}
|
// }
|
||||||
double CameraBase::getExposure()
|
// double CameraBase::getExposure()
|
||||||
{
|
// {
|
||||||
return this->_exposure;
|
// return this->_exposure;
|
||||||
}
|
// }
|
||||||
bool CameraBase::isRunning()
|
// bool CameraBase::isRunning()
|
||||||
{
|
// {
|
||||||
return this->_is_running;
|
// return this->_is_running;
|
||||||
}
|
// }
|
||||||
|
|
||||||
void CameraBase::openImpl()
|
// void CameraBase::openImpl()
|
||||||
{
|
// {
|
||||||
|
|
||||||
}
|
// }
|
||||||
void CameraBase::open(CameraType type, int id)
|
// void CameraBase::open(CameraType type, int id)
|
||||||
{
|
// {
|
||||||
this->_type = type;
|
// this->_type = type;
|
||||||
this->_camera_id = id;
|
// this->_camera_id = id;
|
||||||
|
|
||||||
openImpl();
|
// openImpl();
|
||||||
|
|
||||||
if (this->_cap.isOpened())
|
// if (this->_cap.isOpened())
|
||||||
{
|
// {
|
||||||
std::cout << "Camera opened!" << std::endl;
|
// std::cout << "Camera opened!" << std::endl;
|
||||||
this->_is_running = true;
|
// this->_is_running = true;
|
||||||
this->_tt = std::thread(&CameraBase::_run, this);
|
// this->_tt = std::thread(&CameraBase::_run, this);
|
||||||
this->_tt.detach();
|
// this->_tt.detach();
|
||||||
}
|
// }
|
||||||
else if (type != CameraType::NONE)
|
// else if (type != CameraType::NONE)
|
||||||
{
|
// {
|
||||||
std::cout << "Camera can NOT open!" << std::endl;
|
// std::cout << "Camera can NOT open!" << std::endl;
|
||||||
}
|
// }
|
||||||
}
|
// }
|
||||||
void CameraBase::_run()
|
// void CameraBase::_run()
|
||||||
{
|
// {
|
||||||
while (this->_is_running && this->_cap.isOpened())
|
// while (this->_is_running && this->_cap.isOpened())
|
||||||
{
|
// {
|
||||||
this->_cap >> this->_frame;
|
// this->_cap >> this->_frame;
|
||||||
this->_is_updated = true;
|
// this->_is_updated = true;
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(2));
|
// std::this_thread::sleep_for(std::chrono::milliseconds(2));
|
||||||
}
|
// }
|
||||||
}
|
// }
|
||||||
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)
|
// if (this->_type != CameraType::NONE)
|
||||||
{
|
// {
|
||||||
int n_try = 0;
|
// int n_try = 0;
|
||||||
while (n_try < 5000)
|
// while (n_try < 5000)
|
||||||
{
|
// {
|
||||||
if (this->_is_updated)
|
// if (this->_is_updated)
|
||||||
{
|
// {
|
||||||
this->_is_updated = false;
|
// this->_is_updated = false;
|
||||||
this->_frame.copyTo(image);
|
// this->_frame.copyTo(image);
|
||||||
break;
|
// break;
|
||||||
}
|
// }
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(20));
|
// std::this_thread::sleep_for(std::chrono::milliseconds(20));
|
||||||
n_try ++;
|
// n_try ++;
|
||||||
}
|
// }
|
||||||
}
|
// }
|
||||||
if (image.cols == 0 || image.rows == 0)
|
// if (image.cols == 0 || image.rows == 0)
|
||||||
{
|
// {
|
||||||
throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");
|
// throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");
|
||||||
}
|
// }
|
||||||
return image.cols > 0 && image.rows > 0;
|
// return image.cols > 0 && image.rows > 0;
|
||||||
}
|
// }
|
||||||
void CameraBase::release()
|
// void CameraBase::release()
|
||||||
{
|
// {
|
||||||
_cap.release();
|
// _cap.release();
|
||||||
}
|
// }
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -1,25 +1,30 @@
|
|||||||
|
#if 0
|
||||||
#include "sv_video_input.h"
|
#include "sv_video_input.h"
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
namespace sv {
|
namespace sv {
|
||||||
|
|
||||||
|
|
||||||
Camera::Camera()
|
Camera::Camera()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
Camera::~Camera()
|
Camera::~Camera()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void Camera::openImpl()
|
void Camera::openImpl()
|
||||||
{
|
{
|
||||||
if (this->_type == CameraType::WEBCAM)
|
if (this->_type == CameraType::WEBCAM || this->_type == CameraType::V4L2CAM)
|
||||||
{
|
{
|
||||||
this->_cap.open(this->_camera_id);
|
if (this->_type == CameraType::V4L2CAM)
|
||||||
|
{
|
||||||
|
this->_cap.open(this->_camera_id, cv::CAP_V4L2);
|
||||||
|
}
|
||||||
|
if (this->_type == CameraType::WEBCAM)
|
||||||
|
{
|
||||||
|
this->_cap.open(this->_camera_id);
|
||||||
|
}
|
||||||
if (this->_width > 0 && this->_height > 0)
|
if (this->_width > 0 && this->_height > 0)
|
||||||
{
|
{
|
||||||
this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width);
|
this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width);
|
||||||
@@ -74,6 +79,37 @@ void Camera::openImpl()
|
|||||||
#ifdef PLATFORM_JETSON
|
#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);
|
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);
|
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
|
#endif
|
||||||
}
|
}
|
||||||
else if (this->_type == CameraType::MIPI)
|
else if (this->_type == CameraType::MIPI)
|
||||||
@@ -91,9 +127,9 @@ void Camera::openImpl()
|
|||||||
|
|
||||||
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);
|
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.open(pipe, cv::CAP_GSTREAMER);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
Reference in New Issue
Block a user