From 169f4ba55b3a9cac479bdf4589b5b900210f56d5 Mon Sep 17 00:00:00 2001 From: AiYangSky <1732570904@qq.com> Date: Tue, 21 Nov 2023 15:27:21 +0800 Subject: [PATCH 1/9] temporary storage --- CMakeLists.txt | 5 +- build_on_x86_cuda.sh | 2 +- gimbal_ctrl/driver/src/CMakeLists.txt | 3 +- gimbal_ctrl/driver/src/GX40/CMakeLists.txt | 18 ++ .../driver/src/GX40/GX40_gimbal_crc16.h | 41 +++ .../driver/src/GX40/GX40_gimbal_driver.cpp | 301 ++++++++++++++++++ .../driver/src/GX40/GX40_gimbal_driver.h | 88 +++++ .../driver/src/GX40/GX40_gimbal_funtion.cpp | 251 +++++++++++++++ .../driver/src/GX40/GX40_gimbal_struct.h | 154 +++++++++ gimbal_ctrl/driver/src/amov_gimbal.cpp | 75 +++-- gimbal_ctrl/driver/src/amov_gimbal.h | 18 +- gimbal_ctrl/driver/src/amov_gimbal_private.h | 15 +- gimbal_ctrl/driver/src/amov_gimbal_struct.h | 33 +- gimbal_ctrl/driver/src/amov_tool.h | 2 +- gimbal_ctrl/sv_gimbal.cpp | 5 +- include/sv_gimbal.h | 1 + include/sv_video_base.h | 2 +- .../demo/detection_with_clicked_tracking.cpp | 10 +- ...gimbal_detection_with_clicked_tracking.cpp | 13 +- .../demo/gimbal_udp_detection_info_sender.cpp | 14 +- .../x86-cuda/x86-opencv470-cuda-install.sh | 15 +- scripts/x86-cuda/x86-opencv470-install.sh | 23 +- video_io/sv_video_base.cpp | 2 +- video_io/sv_video_input.cpp | 183 ++++++----- 24 files changed, 1130 insertions(+), 144 deletions(-) create mode 100755 gimbal_ctrl/driver/src/GX40/CMakeLists.txt create mode 100644 gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h create mode 100644 gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp create mode 100644 gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h create mode 100644 gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp create mode 100644 gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h diff --git a/CMakeLists.txt b/CMakeLists.txt index c2986df..25aca72 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -69,6 +69,7 @@ include_directories( ${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/Q10f + ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/GX40 ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl ${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/color_line ${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}/utils ) @@ -139,6 +140,8 @@ file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/AT10/ list(APPEND driver_SRCS ${DRV_LIB_FILES}) file(GLOB DRV_LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/Q10f/*.cpp) 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) list(APPEND driver_SRCS ${DRV_LIB_FILES}) diff --git a/build_on_x86_cuda.sh b/build_on_x86_cuda.sh index 2b9fd36..d7591c0 100755 --- a/build_on_x86_cuda.sh +++ b/build_on_x86_cuda.sh @@ -4,6 +4,6 @@ rm -rf build mkdir build cd build cmake .. -DPLATFORM=X86_CUDA -make -j4 +make -j sudo make install diff --git a/gimbal_ctrl/driver/src/CMakeLists.txt b/gimbal_ctrl/driver/src/CMakeLists.txt index 5421bce..33451f7 100755 --- a/gimbal_ctrl/driver/src/CMakeLists.txt +++ b/gimbal_ctrl/driver/src/CMakeLists.txt @@ -10,9 +10,9 @@ add_definitions( add_subdirectory(FIFO) ########## add types of gimbal ############## add_subdirectory(G1) -add_subdirectory(G2) add_subdirectory(Q10f) add_subdirectory(AT10) +add_subdirectory(GX40) file(GLOB LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp) @@ -27,6 +27,7 @@ target_link_libraries(AMOV_Gimbal Gimabl_G2 Gimabl_Q10f Gimabl_AT10 + Gimabl_GX40 ) target_include_directories(AMOV_Gimbal diff --git a/gimbal_ctrl/driver/src/GX40/CMakeLists.txt b/gimbal_ctrl/driver/src/GX40/CMakeLists.txt new file mode 100755 index 0000000..849562c --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/CMakeLists.txt @@ -0,0 +1,18 @@ +add_library(Gimabl_GX40) + +file(GLOB LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp) + +target_sources(Gimabl_GX40 + PUBLIC + ${LIB_FILES} +) + +target_link_libraries(Gimabl_GX40 + PUBLIC + FIFO +) + +target_include_directories(Gimabl_GX40 + PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} +) \ No newline at end of file diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h new file mode 100644 index 0000000..f3bd6c1 --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h @@ -0,0 +1,41 @@ +/* + * @Description: + * @Author: L LC @amov + * @Date: 2023-10-20 16:33:07 + * @LastEditors: L LC @amov + * @LastEditTime: 2023-11-01 17:03:16 + * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_crc16.h + */ +#ifndef GX40_GIMBAL_CRC16_H +#define GX40_GIMBAL_CRC16_H + +#include + +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 \ No newline at end of file diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp new file mode 100644 index 0000000..e03664d --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp @@ -0,0 +1,301 @@ +/* + * @Description: + * @Author: L LC @amov + * @Date: 2023-10-20 16:08:17 + * @LastEditors: L LC @amov + * @LastEditTime: 2023-11-16 17:23:38 + * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_driver.cpp + */ +#include +#include "GX40_gimbal_driver.h" +#include "GX40_gimbal_crc16.h" +#include + +/** + * 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(amovGimbal::pStateInvoke callback) +{ + this->updateGimbalStateCallback = callback; + + 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::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(buf); + primary = (GX40::GIMBAL_PRIMARY_SLAVE_FRAME_T *)temp->primaryData; + secondary = (GX40::GIMBAL_SECONDARY_SLAVE_FRAME_T *)temp->secondaryData; + + mState.lock(); + this->state.workMode = (amovGimbal::AMOV_GIMBAL_SERVO_MODE_T)primary->workMode; + this->state.cameraFlag = (amovGimbal::AMOV_GIMBAL_CAMERA_FLAG_T)primary->state; + // 应该需要再解算一下,才能出具体的框架角度 + this->state.rel.yaw = 360.0f - (primary->motorYaw * XF_ANGLE_DPI); + 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); + + 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. + */ +#include +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; +} \ No newline at end of file diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h new file mode 100644 index 0000000..a3df9ba --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h @@ -0,0 +1,88 @@ + +/* + * @Description: + * @Author: L LC @amov + * @Date: 2023-10-20 16:08:13 + * @LastEditors: L LC @amov + * @LastEditTime: 2023-11-16 17:23:27 + * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_driver.h + */ +#include "../amov_gimbal.h" +#include "../amov_gimbal_private.h" +#include "GX40_gimbal_struct.h" +#include +#include +#include +#include +#include + +#ifndef __GX40_DRIVER_H +#define __GX40_DRIVER_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]; + + amovGimbal::AMOV_GIMBAL_POS_T carrierPos; + amovGimbal::AMOV_GIMBAL_VELOCITY_T carrierSpeed; + amovGimbal::AMOV_GIMBAL_VELOCITY_T carrierAcc; + GX40::GIMBAL_SECONDARY_MASTER_FRAME_T carrierGNSS; + + std::thread::native_handle_type nopSendThreadHandle; + void nopSend(void); + void parserStart(amovGimbal::pStateInvoke callback); + +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 amovGimbal::AMOV_GIMBAL_POS_T &pos); + uint32_t setGimabalSpeed(const amovGimbal::AMOV_GIMBAL_POS_T &speed); + uint32_t setGimabalHome(void); + + uint32_t setGimbalZoom(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0); + uint32_t setGimbalFocus(amovGimbal::AMOV_GIMBAL_ZOOM_T zoom, float targetRate = 0); + + uint32_t takePic(void); + uint32_t setVideo(const amovGimbal::AMOV_GIMBAL_VIDEO_T newState); + uint32_t attitudeCorrection(const amovGimbal::AMOV_GIMBAL_POS_T &pos, + const amovGimbal::AMOV_GIMBAL_VELOCITY_T &seppd, + const amovGimbal::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 diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp new file mode 100644 index 0000000..ae33e6a --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp @@ -0,0 +1,251 @@ +/* + * @Description: + * @Author: L LC @amov + * @Date: 2023-11-02 17:50:26 + * @LastEditors: L LC @amov + * @LastEditTime: 2023-11-16 17:23:07 + * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_funtion.cpp + */ +#include +#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 "amovGimbal::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 amovGimbal::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 "amovGimbal::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 amovGimbal::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 `amovGimbal::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 amovGimbal::AMOV_GIMBAL_VIDEO_T newState) +{ + uint8_t temp = 0X01; + + mState.lock(); + if (state.video == amovGimbal::AMOV_GIMBAL_VIDEO_TAKE) + { + state.video = amovGimbal::AMOV_GIMBAL_VIDEO_OFF; + } + else + { + state.video = amovGimbal::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 "amovGimbal::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 + * `amovGimbal::AMOV_GIMBAL_VELOCITY_T`. + * @param acc The "acc" parameter is of type "amovGimbal::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(amovGimbal::AMOV_GIMBAL_POS_T), + * sizeof(amovGimbal::AMOV_GIMBAL_VELOCITY_T), and sizeof(amovGimbal::AMOV_GIMBAL_VELOCITY_T). + */ +uint32_t GX40GimbalDriver::attitudeCorrection(const amovGimbal::AMOV_GIMBAL_POS_T &pos, + const amovGimbal::AMOV_GIMBAL_VELOCITY_T &seppd, + const amovGimbal::AMOV_GIMBAL_VELOCITY_T &acc, + void *extenData) +{ + carrierStateMutex.lock(); + carrierPos = pos; + carrierSpeed = seppd; + carrierAcc = acc; + upDataTs = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()); + carrierStateMutex.unlock(); + return sizeof(amovGimbal::AMOV_GIMBAL_POS_T) + sizeof(amovGimbal::AMOV_GIMBAL_VELOCITY_T) + sizeof(amovGimbal::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 amovGimbal::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(amovGimbal::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 amovGimbal::AMOV_GIMBAL_ZOOM_IN: + temp[0] = GX40::GIMBAL_CMD_ZOMM_IN; + break; + case amovGimbal::AMOV_GIMBAL_ZOOM_OUT: + temp[0] = GX40::GIMBAL_CMD_ZOOM_OUT; + break; + case amovGimbal::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 amovGimbal::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(amovGimbal::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; + carrierGNSS.lat = lat; + carrierGNSS.alt = alt; + + carrierGNSS.relAlt = relAlt; + carrierGNSS.nState = nState; + + carrierStateMutex.unlock(); + return sizeof(GX40::GIMBAL_SECONDARY_MASTER_FRAME_T); +} diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h new file mode 100644 index 0000000..2447da2 --- /dev/null +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h @@ -0,0 +1,154 @@ +/* + * @Description: + * @Author: L LC @amov + * @Date: 2023-10-20 16:08:13 + * @LastEditors: L LC @amov + * @LastEditTime: 2023-11-16 17:27:05 + * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_struct.h + */ +#ifndef GX40_GIMBAL_STRUCT_H +#define GX40_GIMBAL_STRUCT_H + +#include + +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 diff --git a/gimbal_ctrl/driver/src/amov_gimbal.cpp b/gimbal_ctrl/driver/src/amov_gimbal.cpp index a0e9190..af39154 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal.cpp +++ b/gimbal_ctrl/driver/src/amov_gimbal.cpp @@ -3,15 +3,15 @@ * @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 + * @LastEditTime: 2023-11-16 17:27:28 + * @FilePath: gimbal_ctrl/driver/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 "GX40_gimbal_driver.h" #include #include @@ -19,30 +19,18 @@ #include #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 callbackMap; - std::map 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}}; + {"AT10", AT10GimbalDriver::creat}, + {"GX40", GX40GimbalDriver::creat}}; } /* The amovGimbalCreator class is a factory class that creates an instance of the amovGimbal class */ @@ -133,6 +121,11 @@ void amovGimbal::amovGimbalBase::send(void) if (state) { IO->outPutBytes((uint8_t *)&tempBuffer, calPackLen(tempBuffer)); + // printf("\r\n"); + // for(uint16_t i =0 ; i< calPackLen(tempBuffer);i++) + // { + // printf("%02X ",tempBuffer[i]); + // } } } } @@ -186,6 +179,10 @@ void amovGimbal::amovGimbalBase::stackStart(void) } std::thread parserLoop(&amovGimbalBase::parserLoop, this); std::thread sendLoop(&amovGimbalBase::sendLoop, this); + + this->sendThreadHanle = sendLoop.native_handle(); + this->parserThreadHanle = parserLoop.native_handle(); + parserLoop.detach(); sendLoop.detach(); } @@ -203,12 +200,19 @@ void amovGimbal::gimbal::setParserCallback(amovGimbal::pStateInvoke callback) ((amovGimbalBase *)(this->dev))->updateGimbalStateCallback = callback; } +void amovGimbal::amovGimbalBase::nodeSet(SET uint32_t _self, SET uint32_t _remote) +{ + return; +} + void amovGimbal::amovGimbalBase::parserStart(pStateInvoke callback) { this->updateGimbalStateCallback = callback; std::thread mainLoop(&amovGimbalBase::mainLoop, this); + this->stackThreadHanle = mainLoop.native_handle(); + mainLoop.detach(); } /** @@ -235,11 +239,6 @@ amovGimbal::AMOV_GIMBAL_STATE_T amovGimbal::gimbal::getGimabalState(void) /** * 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; @@ -300,6 +299,36 @@ uint32_t amovGimbal::IamovGimbalBase::extensionFuntions(void *cmd) return 0; } +uint32_t amovGimbal::IamovGimbalBase::setGNSSInfo(float lng, float lat, float alt, uint32_t nState, float relAlt) +{ + return 0; +} + +bool amovGimbal::IamovGimbalBase::setGimbalPosBlock(const amovGimbal::AMOV_GIMBAL_POS_T &pos) +{ + return false; +} + +bool amovGimbal::IamovGimbalBase::setGimabalHomeBlock(void) +{ + return false; +} + +bool amovGimbal::IamovGimbalBase::setGimbalZoomBlock(float targetRate) +{ + return false; +} + +bool amovGimbal::IamovGimbalBase::takePicBlock(void) +{ + return false; +} + +bool amovGimbal::IamovGimbalBase::calibrationBlock(void) +{ + return false; +} + /** * 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 @@ -317,7 +346,7 @@ amovGimbal::gimbal::gimbal(const std::string &type, IOStreamBase *_IO, dev = amovGimbalCreator::createAmovGimbal(typeName, IO); - dev->nodeSet(_self, _remote); + ((amovGimbalBase *)(dev))->nodeSet(_self, _remote); } amovGimbal::gimbal::~gimbal() diff --git a/gimbal_ctrl/driver/src/amov_gimbal.h b/gimbal_ctrl/driver/src/amov_gimbal.h index 442f91f..5b74ee9 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal.h +++ b/gimbal_ctrl/driver/src/amov_gimbal.h @@ -3,8 +3,8 @@ * @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 + * @LastEditTime: 2023-11-14 13:57:33 + * @FilePath: gimbal_ctrl/driver/src/amov_gimbal.h */ #ifndef AMOV_GIMBAL_H @@ -32,7 +32,6 @@ namespace amovGimbal { } - // Control data input and output class IOStreamBase { @@ -55,11 +54,12 @@ namespace amovGimbal public: IamovGimbalBase() {} virtual ~IamovGimbalBase() {} - // functions - virtual void nodeSet(SET uint32_t _self, SET uint32_t _remote); + + // 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); @@ -68,7 +68,15 @@ namespace amovGimbal 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 gimbal diff --git a/gimbal_ctrl/driver/src/amov_gimbal_private.h b/gimbal_ctrl/driver/src/amov_gimbal_private.h index aace061..2e354c2 100644 --- a/gimbal_ctrl/driver/src/amov_gimbal_private.h +++ b/gimbal_ctrl/driver/src/amov_gimbal_private.h @@ -3,8 +3,8 @@ * @Author : Aiyangsky * @Date : 2023-05-13 10:39:20 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-16 22:30:53 - * @FilePath: /gimbal-sdk-multi-platform/src/amov_gimbal_private.h + * @LastEditTime: 2023-11-14 10:35:56 + * @FilePath: gimbal_ctrl/driver/src/amov_gimbal_private.h */ #ifndef __AMOV_GIMABL_PRIVATE_H #define __AMOV_GIMABL_PRIVATE_H @@ -35,6 +35,10 @@ namespace amovGimbal fifoRing *rxQueue; fifoRing *txQueue; + std::thread::native_handle_type parserThreadHanle = 0; + std::thread::native_handle_type sendThreadHanle = 0; + std::thread::native_handle_type stackThreadHanle = 0; + PamovGimbalBase(SET IOStreamBase *_IO) { IO = _IO; @@ -49,6 +53,11 @@ namespace amovGimbal { 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); } }; @@ -70,6 +79,8 @@ namespace amovGimbal virtual void stackStart(void); virtual void parserStart(amovGimbal::pStateInvoke callback); + virtual void nodeSet(SET uint32_t _self, SET uint32_t _remote); + public: amovGimbalBase(IOStreamBase *_IO); virtual ~amovGimbalBase(); diff --git a/gimbal_ctrl/driver/src/amov_gimbal_struct.h b/gimbal_ctrl/driver/src/amov_gimbal_struct.h index a7451b0..e68f4d2 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/amov_gimbal_struct.h @@ -3,8 +3,8 @@ * @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 + * @LastEditTime: 2023-10-23 18:05:59 + * @FilePath: gimbal_ctrl/driver/src/amov_gimbal_struct.h */ #include @@ -21,9 +21,22 @@ namespace amovGimbal typedef enum { - AMOV_GIMBAL_MODE_LOCK, - AMOV_GIMBAL_MODE_NULOCK, - } AMOV_GIMBAL_MODE_T; + 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 { @@ -53,10 +66,12 @@ namespace amovGimbal typedef struct { - AMOV_GIMBAL_MODE_T workMode; + 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; @@ -79,9 +94,9 @@ namespace amovGimbal typedef struct { - double x; - double y; - double z; + double x; // or N + double y; // or E + double z; // or UP } AMOV_GIMBAL_VELOCITY_T; } // namespace amovGimbal diff --git a/gimbal_ctrl/driver/src/amov_tool.h b/gimbal_ctrl/driver/src/amov_tool.h index e165df6..82c6536 100644 --- a/gimbal_ctrl/driver/src/amov_tool.h +++ b/gimbal_ctrl/driver/src/amov_tool.h @@ -4,7 +4,7 @@ * @Date: 2023-07-31 18:30:33 * @LastEditors: L LC @amov * @LastEditTime: 2023-07-31 18:55:18 - * @FilePath: /gimbal-sdk-multi-platform/src/amov_tool.h + * @FilePath: gimbal_ctrl/driver/src/amov_tool.h */ namespace amovGimbalTools diff --git a/gimbal_ctrl/sv_gimbal.cpp b/gimbal_ctrl/sv_gimbal.cpp index d01406c..43e941d 100644 --- a/gimbal_ctrl/sv_gimbal.cpp +++ b/gimbal_ctrl/sv_gimbal.cpp @@ -24,7 +24,8 @@ namespace sv { {GimbalType::G1, "G1"}, {GimbalType::Q10f, "Q10f"}, - {GimbalType::AT10, "AT10"}}; + {GimbalType::AT10, "AT10"}, + {GimbalType::GX40, "GX40"}}; std::string &cvGimbalType2Str(const GimbalType &type) { @@ -191,11 +192,13 @@ void sv::Gimbal::removeIO(sv::Gimbal *dev) * * @return A boolean value is being returned. */ +#include "stdlib.h" bool sv::Gimbal::open(PStateInvoke callback) { bool ret = false; this->IO = creatIO(this); + if (this->IO != nullptr) { std::string driverName; diff --git a/include/sv_gimbal.h b/include/sv_gimbal.h index 445f257..31cd858 100644 --- a/include/sv_gimbal.h +++ b/include/sv_gimbal.h @@ -27,6 +27,7 @@ namespace sv G1, Q10f, AT10, + GX40, }; enum class GimbalLink { diff --git a/include/sv_video_base.h b/include/sv_video_base.h index 5c20051..40eb265 100644 --- a/include/sv_video_base.h +++ b/include/sv_video_base.h @@ -326,7 +326,7 @@ protected: }; -enum class CameraType {NONE, WEBCAM, G1, Q10, MIPI}; +enum class CameraType {NONE, WEBCAM, G1, Q10, MIPI, GX40}; class CameraBase { public: diff --git a/samples/demo/detection_with_clicked_tracking.cpp b/samples/demo/detection_with_clicked_tracking.cpp index 7cefc72..3bd5a07 100644 --- a/samples/demo/detection_with_clicked_tracking.cpp +++ b/samples/demo/detection_with_clicked_tracking.cpp @@ -2,6 +2,8 @@ #include // 包含SpireCV SDK头文件 #include +#include +#include using namespace std; @@ -48,13 +50,17 @@ int main(int argc, char *argv[]) { // 打开摄像头 - sv::Camera cap; + // sv::Camera cap; // cap.setWH(640, 480); // cap.setFps(30); - cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0 + // cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0 // cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4"); // 实例化OpenCV的Mat类,用于内存单帧图像 + + cv::VideoCapture cap; + cap.open("/dev/video0"); cv::Mat img; + int frame_id = 0; while (1) { diff --git a/samples/demo/gimbal_detection_with_clicked_tracking.cpp b/samples/demo/gimbal_detection_with_clicked_tracking.cpp index c9d1800..441fd26 100644 --- a/samples/demo/gimbal_detection_with_clicked_tracking.cpp +++ b/samples/demo/gimbal_detection_with_clicked_tracking.cpp @@ -54,7 +54,7 @@ void gimbalNoTrack(void) int main(int argc, char *argv[]) { // 实例化吊舱 - gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL); + gimbal = new sv::Gimbal(sv::GimbalType::GX40, sv::GimbalLink::SERIAL); // 使用 /dev/ttyUSB0 作为控制串口 gimbal->setSerialPort("/dev/ttyUSB0"); // 以GimableCallback作为状态回调函数启用吊舱控制 @@ -62,13 +62,13 @@ int main(int argc, char *argv[]) // 定义相机 sv::Camera cap; // 设置相机流媒体地址为 192.168.2.64 - cap.setIp("192.168.2.64"); + cap.setIp("192.168.144.108"); // 设置获取画面分辨率为720P cap.setWH(1280, 720); // 设置视频帧率为30帧 cap.setFps(30); // 开启相机 - cap.open(sv::CameraType::G1); + cap.open(sv::CameraType::GX40); // 定义一个新的窗口,可在上面进行框选操作 cv::namedWindow(RGB_WINDOW); @@ -77,10 +77,10 @@ int main(int argc, char *argv[]) // 实例化 框选目标跟踪类 sv::SingleObjectTracker sot; // 手动导入相机参数,如果使用Amov的G1等吊舱或相机,则可以忽略该步骤,将自动下载相机参数文件 - sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml"); + sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml"); sv::CommonObjectDetector cod; - cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml"); + cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml"); // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; @@ -94,6 +94,7 @@ int main(int argc, char *argv[]) // 读取一帧图像到img cap.read(img); cv::resize(img, img, cv::Size(cod.image_width, cod.image_height)); + cv::imshow(RGB_WINDOW, img); // 执行通用目标检测 cod.detect(img, tgts); @@ -200,7 +201,7 @@ int main(int argc, char *argv[]) } } // end of tracking // 显示检测结果img - cv::imshow(RGB_WINDOW, img); + // cv::imshow(RGB_WINDOW, img); cv::waitKey(10); } return 0; diff --git a/samples/demo/gimbal_udp_detection_info_sender.cpp b/samples/demo/gimbal_udp_detection_info_sender.cpp index 00bfceb..27a3cbd 100644 --- a/samples/demo/gimbal_udp_detection_info_sender.cpp +++ b/samples/demo/gimbal_udp_detection_info_sender.cpp @@ -44,7 +44,7 @@ void onMouse(int event, int x, int y, int, void *); int main(int argc, char *argv[]) { // 实例化吊舱 - gimbal = new sv::Gimbal(sv::GimbalType::G1, sv::GimbalLink::SERIAL); + gimbal = new sv::Gimbal(sv::GimbalType::GX40, sv::GimbalLink::SERIAL); // 使用 /dev/ttyUSB0 作为控制串口 gimbal->setSerialPort("/dev/ttyUSB0"); // 以gimableCallback作为状态回调函数启用吊舱控制 @@ -52,13 +52,13 @@ int main(int argc, char *argv[]) // 定义相机 sv::Camera cap; // 设置相机流媒体地址为 192.168.2.64 - cap.setIp("192.168.2.64"); + cap.setIp("192.168.144.108"); // 设置获取画面分辨率为720P - cap.setWH(1280, 720); - // 设置视频帧率为30帧 - cap.setFps(30); + // cap.setWH(1280, 720); + // // 设置视频帧率为30帧 + // cap.setFps(30); // 开启相机 - cap.open(sv::CameraType::G1); + cap.open(sv::CameraType::GX40); // 定义一个窗口 才可以在上面操作 cv::namedWindow(RGB_WINDOW); @@ -80,6 +80,8 @@ int main(int argc, char *argv[]) // 读取一帧图像到img cap.read(img); + std::cout << img.type() << std::endl; + // 执行Aruco二维码检测 ad.detect(img, tgts); diff --git a/scripts/x86-cuda/x86-opencv470-cuda-install.sh b/scripts/x86-cuda/x86-opencv470-cuda-install.sh index c44e718..8917d9a 100755 --- a/scripts/x86-cuda/x86-opencv470-cuda-install.sh +++ b/scripts/x86-cuda/x86-opencv470-cuda-install.sh @@ -60,9 +60,20 @@ cmake -D CMAKE_BUILD_TYPE=Release \ -D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda \ -D OPENCV_ENABLE_NONFREE=ON \ -D CMAKE_INSTALL_PREFIX=/usr/local \ - -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. + -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. \ + -D CMAKE_VERBOSE_MAKEFILE=ON \ + -D ENABLE_CXX11=ON \ + -D BUILD_TESTS=OFF \ + -D WITH_GSTREAMER=ON \ + -D OPENCV_GENERATE_PKGCONFIG=ON \ + -D ENABLE_FAST_MATH=ON \ + -D CUDA_FAST_MATH=ON \ + -D BUILD_opencv_python3=ON \ + -D PYTHON3_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.8.so \ + -D PYTHON3_NUMPY_INCLUDE_DIRS=/home/aiyangsky/.local/lib/python3.8/site-packages/numpy/core/include \ + -D PYTHON3_PACKAGES_PATH=/usr/lib/python3/dist-packages -make -j2 +make -j sudo make install cd diff --git a/scripts/x86-cuda/x86-opencv470-install.sh b/scripts/x86-cuda/x86-opencv470-install.sh index df48173..00ab5cb 100755 --- a/scripts/x86-cuda/x86-opencv470-install.sh +++ b/scripts/x86-cuda/x86-opencv470-install.sh @@ -52,13 +52,30 @@ cp -r ~/opencv_build/opencv_cache_x86-4.7.0/* ~/opencv_build/opencv-4.7.0/.cache mkdir build cd build +sudo apt-get 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 + cmake -D CMAKE_BUILD_TYPE=Release \ - -D WITH_CUDA=OFF \ + -D CMAKE_VERBOSE_MAKEFILE=ON \ + -D ENABLE_CXX11=ON \ + -D BUILD_TESTS=OFF \ + -D WITH_GSTREAMER=ON \ + -D OPENCV_GENERATE_PKGCONFIG=ON \ + -D ENABLE_FAST_MATH=ON \ + -D CUDA_FAST_MATH=ON \ + -D WITH_CUBLAS=ON \ + -D WITH_CUDA=ON \ -D OPENCV_ENABLE_NONFREE=ON \ -D CMAKE_INSTALL_PREFIX=/usr/local \ - -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. + -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. \ + -D BUILD_opencv_python3=ON \ + -D PYTHON3_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.8.so \ + -D PYTHON3_NUMPY_INCLUDE_DIRS=/home/aiyangsky/.local/lib/python3.8/site-packages/numpy/core/include \ + -D PYTHON3_PACKAGES_PATH=/usr/lib/python3/dist-packages -make -j2 +make -j sudo make install cd diff --git a/video_io/sv_video_base.cpp b/video_io/sv_video_base.cpp index ea57b54..3e4d974 100644 --- a/video_io/sv_video_base.cpp +++ b/video_io/sv_video_base.cpp @@ -1110,7 +1110,7 @@ void CameraBase::_run() } bool CameraBase::read(cv::Mat& image) { - if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI) + if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI || this->_type == CameraType::GX40) { int n_try = 0; while (n_try < 5000) diff --git a/video_io/sv_video_input.cpp b/video_io/sv_video_input.cpp index 5ca7bfa..5862280 100644 --- a/video_io/sv_video_input.cpp +++ b/video_io/sv_video_input.cpp @@ -2,98 +2,123 @@ #include #include - - -namespace sv { - - -Camera::Camera() +namespace sv { -} -Camera::~Camera() -{ -} - -void Camera::openImpl() -{ - if (this->_type == CameraType::WEBCAM) + Camera::Camera() { - this->_cap.open(this->_camera_id); - if (this->_width > 0 && this->_height > 0) - { - this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width); - this->_cap.set(cv::CAP_PROP_FRAME_HEIGHT, this->_height); - } - if (this->_fps > 0) - { - this->_cap.set(cv::CAP_PROP_FPS, this->_fps); - } - if (this->_brightness > 0) - { - this->_cap.set(cv::CAP_PROP_BRIGHTNESS, this->_brightness); - } - if (this->_contrast > 0) - { - this->_cap.set(cv::CAP_PROP_CONTRAST, this->_contrast); - } - if (this->_saturation > 0) - { - this->_cap.set(cv::CAP_PROP_SATURATION, this->_saturation); - } - if (this->_hue > 0) - { - this->_cap.set(cv::CAP_PROP_HUE, this->_hue); - } - if (this->_exposure > 0) - { - this->_cap.set(cv::CAP_PROP_EXPOSURE, this->_exposure); - } } - else if (this->_type == CameraType::G1) + Camera::~Camera() { - char pipe[512]; - if (this->_width <= 0 || this->_height <= 0) + } + + void Camera::openImpl() + { + if (this->_type == CameraType::WEBCAM) { - this->_width = 1280; - this->_height = 720; + this->_cap.open(this->_camera_id); + if (this->_width > 0 && this->_height > 0) + { + this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width); + this->_cap.set(cv::CAP_PROP_FRAME_HEIGHT, this->_height); + } + if (this->_fps > 0) + { + this->_cap.set(cv::CAP_PROP_FPS, this->_fps); + } + if (this->_brightness > 0) + { + this->_cap.set(cv::CAP_PROP_BRIGHTNESS, this->_brightness); + } + if (this->_contrast > 0) + { + this->_cap.set(cv::CAP_PROP_CONTRAST, this->_contrast); + } + if (this->_saturation > 0) + { + this->_cap.set(cv::CAP_PROP_SATURATION, this->_saturation); + } + if (this->_hue > 0) + { + this->_cap.set(cv::CAP_PROP_HUE, this->_hue); + } + if (this->_exposure > 0) + { + this->_cap.set(cv::CAP_PROP_EXPOSURE, this->_exposure); + } } - if (this->_port <= 0) + else if (this->_type == CameraType::G1) { - this->_port = 554; - } - if (this->_fps <= 0) - { - this->_fps = 30; - } + char pipe[512]; + if (this->_width <= 0 || this->_height <= 0) + { + this->_width = 1280; + this->_height = 720; + } + if (this->_port <= 0) + { + this->_port = 554; + } + if (this->_fps <= 0) + { + this->_fps = 30; + } #ifdef PLATFORM_X86_CUDA - sprintf(pipe, "rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps); - this->_cap.open(pipe); + sprintf(pipe, "rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps); + this->_cap.open(pipe); #endif #ifdef PLATFORM_JETSON - sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps); - this->_cap.open(pipe, cv::CAP_GSTREAMER); + sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps); + this->_cap.open(pipe, cv::CAP_GSTREAMER); #endif + } + else if (this->_type == CameraType::GX40) + { + std::ostringstream camera_url; + if (this->_width <= 0 || this->_height <= 0) + { + this->_width = 1280; + this->_height = 720; + } + if (this->_port <= 0) + { + this->_port = 554; + } +#ifdef PLATFORM_X86_CUDA + camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port + << "/cam/realmonitor?channel=1&subtype=0 latency=100 ! application/x-rtp,media=video ! \ + rtph265depay ! parsebin ! avdec_h265 ! \ + appsink sync=false"; + std::cout << camera_url.str()<_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=" << this->_width << ",height=" << this->_height << " ! videoconvert ! \ + appsink sync=false"; + this->_cap.open(camera_url.str(),cv::CAP_GSTREAMER); +#endif + } + else if (this->_type == CameraType::MIPI) + { + char pipe[512]; + if (this->_width <= 0 || this->_height <= 0) + { + this->_width = 1280; + this->_height = 720; + } + if (this->_fps <= 0) + { + this->_fps = 30; + } + + sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height); + this->_cap.open(pipe, cv::CAP_GSTREAMER); + } } - else if (this->_type == CameraType::MIPI) - { - char pipe[512]; - if (this->_width <= 0 || this->_height <= 0) - { - this->_width = 1280; - this->_height = 720; - } - if (this->_fps <= 0) - { - this->_fps = 30; - } - - sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height); - this->_cap.open(pipe, cv::CAP_GSTREAMER); - } -} - } - From e46c02cdf7c6ab43c631888fba37b96727bbf5e1 Mon Sep 17 00:00:00 2001 From: AiYangSky <1732570904@qq.com> Date: Wed, 22 Nov 2023 18:59:55 +0800 Subject: [PATCH 2/9] GX40 Done --- .../driver/src/GX40/GX40_gimbal_driver.cpp | 7 ++++--- ...gimbal_detection_with_clicked_tracking.cpp | 3 +-- .../demo/gimbal_udp_detection_info_sender.cpp | 20 +++++++++---------- video_io/sv_video_input.cpp | 15 +++++++------- 4 files changed, 23 insertions(+), 22 deletions(-) diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp index e03664d..7c09a02 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp @@ -163,12 +163,13 @@ void GX40GimbalDriver::convert(void *buf) this->state.workMode = (amovGimbal::AMOV_GIMBAL_SERVO_MODE_T)primary->workMode; this->state.cameraFlag = (amovGimbal::AMOV_GIMBAL_CAMERA_FLAG_T)primary->state; // 应该需要再解算一下,才能出具体的框架角度 - this->state.rel.yaw = 360.0f - (primary->motorYaw * XF_ANGLE_DPI); + 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.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); diff --git a/samples/demo/gimbal_detection_with_clicked_tracking.cpp b/samples/demo/gimbal_detection_with_clicked_tracking.cpp index 441fd26..d6b924b 100644 --- a/samples/demo/gimbal_detection_with_clicked_tracking.cpp +++ b/samples/demo/gimbal_detection_with_clicked_tracking.cpp @@ -94,7 +94,6 @@ int main(int argc, char *argv[]) // 读取一帧图像到img cap.read(img); cv::resize(img, img, cv::Size(cod.image_width, cod.image_height)); - cv::imshow(RGB_WINDOW, img); // 执行通用目标检测 cod.detect(img, tgts); @@ -201,7 +200,7 @@ int main(int argc, char *argv[]) } } // end of tracking // 显示检测结果img - // cv::imshow(RGB_WINDOW, img); + cv::imshow(RGB_WINDOW, img); cv::waitKey(10); } return 0; diff --git a/samples/demo/gimbal_udp_detection_info_sender.cpp b/samples/demo/gimbal_udp_detection_info_sender.cpp index 27a3cbd..0d826df 100644 --- a/samples/demo/gimbal_udp_detection_info_sender.cpp +++ b/samples/demo/gimbal_udp_detection_info_sender.cpp @@ -7,21 +7,21 @@ using namespace std; // yaw roll pitch double gimbalEulerAngle[3]; -void gimableCallback(double &imu_ang_r, double &imu_ang_p, double &imu_ang_y, - double &frame_ang_r, double &frame_ang_p, double &frame_ang_y, +void gimableCallback(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) { static int count = 0; if (count == 25) { - std::cout << "GIMBAL_CMD_RCV_POS" << std::endl; - std::cout << "=============================================" << std::endl; - std::cout << "HALL_yaw:" << frame_ang_y << " " << std::endl; - std::cout << "HALL_roll:" << frame_ang_r << " " << std::endl; - std::cout << "HALL_pitch:" << frame_ang_p << " " << std::endl; - std::cout << "GYRO_yaw:" << imu_ang_y << " " << std::endl; - std::cout << "GYRO_roll:" << imu_ang_r << " " << std::endl; - std::cout << "GYRO_pitch:" << imu_ang_p << " " << std::endl; + // std::cout << "GIMBAL_CMD_RCV_POS" << std::endl; + // std::cout << "=============================================" << std::endl; + // std::cout << "HALL_yaw:" << frame_ang_y << " " << std::endl; + // std::cout << "HALL_roll:" << frame_ang_r << " " << std::endl; + // std::cout << "HALL_pitch:" << frame_ang_p << " " << std::endl; + // std::cout << "GYRO_yaw:" << imu_ang_y << " " << std::endl; + // std::cout << "GYRO_roll:" << imu_ang_r << " " << std::endl; + // std::cout << "GYRO_pitch:" << imu_ang_p << " " << std::endl; count = 0; } diff --git a/video_io/sv_video_input.cpp b/video_io/sv_video_input.cpp index 5862280..1a3c6ae 100644 --- a/video_io/sv_video_input.cpp +++ b/video_io/sv_video_input.cpp @@ -86,21 +86,22 @@ namespace sv this->_port = 554; } #ifdef PLATFORM_X86_CUDA - camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port + 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 ! \ + 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"; - std::cout << camera_url.str()<_cap.open(camera_url.str(),cv::CAP_GSTREAMER); + this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER); #endif #ifdef PLATFORM_JETSON - camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port + 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=" << this->_width << ",height=" << this->_height << " ! videoconvert ! \ + 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); + this->_cap.open(camera_url.str(), cv::CAP_GSTREAMER); #endif } else if (this->_type == CameraType::MIPI) From 469ba77fe6f198ae30523ee63b4487ffe8d3b338 Mon Sep 17 00:00:00 2001 From: AiYangSky <1732570904@qq.com> Date: Tue, 28 Nov 2023 11:54:19 +0800 Subject: [PATCH 3/9] clean up codes --- build_on_x86_cuda.sh | 8 ---- .../driver/src/AT10/AT10_gimbal_crc32.h | 4 +- .../driver/src/AT10/AT10_gimbal_driver.cpp | 4 +- .../driver/src/AT10/AT10_gimbal_driver.h | 4 +- .../driver/src/AT10/AT10_gimbal_funtion.cpp | 4 +- .../driver/src/AT10/AT10_gimbal_struct.h | 4 +- gimbal_ctrl/driver/src/CMakeLists.txt | 37 ------------------- gimbal_ctrl/driver/src/FIFO/CMakeLists.txt | 13 ------- gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp | 4 +- gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h | 4 +- gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h | 4 +- .../driver/src/G1/g1_gimbal_driver.cpp | 4 +- gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h | 4 +- .../driver/src/G1/g1_gimbal_funtion.cpp | 4 +- gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h | 4 +- gimbal_ctrl/driver/src/GX40/CMakeLists.txt | 18 --------- .../driver/src/GX40/GX40_gimbal_crc16.h | 4 +- .../driver/src/GX40/GX40_gimbal_driver.cpp | 4 +- .../driver/src/GX40/GX40_gimbal_driver.h | 4 +- .../driver/src/GX40/GX40_gimbal_funtion.cpp | 4 +- .../driver/src/GX40/GX40_gimbal_struct.h | 4 +- .../driver/src/Q10f/Q10f_gimbal_crc32.h | 4 +- .../driver/src/Q10f/Q10f_gimbal_driver.cpp | 4 +- .../driver/src/Q10f/Q10f_gimbal_driver.h | 4 +- .../driver/src/Q10f/Q10f_gimbal_funtion.cpp | 4 +- .../driver/src/Q10f/Q10f_gimbal_struct.h | 4 +- gimbal_ctrl/driver/src/amov_gimbal.cpp | 4 +- gimbal_ctrl/driver/src/amov_gimbal.h | 4 +- gimbal_ctrl/driver/src/amov_gimbal_private.h | 4 +- gimbal_ctrl/driver/src/amov_gimbal_struct.h | 4 +- gimbal_ctrl/driver/src/amov_tool.h | 4 +- gimbal_ctrl/sv_gimbal.cpp | 4 +- gimbal_ctrl/sv_gimbal_io.hpp | 4 +- 33 files changed, 58 insertions(+), 134 deletions(-) delete mode 100755 gimbal_ctrl/driver/src/CMakeLists.txt delete mode 100755 gimbal_ctrl/driver/src/FIFO/CMakeLists.txt delete mode 100755 gimbal_ctrl/driver/src/GX40/CMakeLists.txt diff --git a/build_on_x86_cuda.sh b/build_on_x86_cuda.sh index bd0ed42..2b9fd36 100755 --- a/build_on_x86_cuda.sh +++ b/build_on_x86_cuda.sh @@ -1,12 +1,4 @@ #!/bin/bash -e -### - # @Description: - # @Author: L LC @amov - # @Date: 2023-11-21 16:10:38 - # @LastEditors: L LC @amov - # @LastEditTime: 2023-11-28 11:27:13 - # @FilePath: /SpireCV/build_on_x86_cuda.sh -### rm -rf build mkdir build diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h index 9a9ce3e..b8845c4 100755 --- a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h +++ b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-16 21:53:43 - * @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_crc32.h + * @LastEditTime: 2023-11-28 11:47:48 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h */ #ifndef AT10_GIMBAL_CRC32_H #define AT10_GIMBAL_CRC32_H diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp index ca8263f..655ca35 100755 --- a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp +++ b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-25 19:39:56 - * @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_driver.cpp + * @LastEditTime: 2023-11-28 11:47:53 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp */ #include "AT10_gimbal_driver.h" #include "AT10_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h index bf84e97..4f2eaf6 100755 --- a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h +++ b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-28 12:24:21 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-25 19:28:55 - * @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_driver.h + * @LastEditTime: 2023-11-28 11:47:58 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h */ #include "../amov_gimbal.h" #include "../amov_gimbal_private.h" diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp index 14b474f..a3993f8 100755 --- a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp +++ b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-03-02 10:00:52 * @LastEditors: L LC @amov - * @LastEditTime: 2023-09-07 10:56:15 - * @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_funtion.cpp + * @LastEditTime: 2023-11-28 11:48:03 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp */ #include "AT10_gimbal_driver.h" #include "AT10_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h index 54f0dee..ee93582 100755 --- a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:07 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-25 19:32:59 - * @FilePath: /gimbal-sdk-multi-platform/src/AT10/AT10_gimbal_struct.h + * @LastEditTime: 2023-11-28 11:48:08 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h */ #ifndef AT10_GIMBAL_STRUCT_H #define AT10_GIMBAL_STRUCT_H diff --git a/gimbal_ctrl/driver/src/CMakeLists.txt b/gimbal_ctrl/driver/src/CMakeLists.txt deleted file mode 100755 index 33451f7..0000000 --- a/gimbal_ctrl/driver/src/CMakeLists.txt +++ /dev/null @@ -1,37 +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(Q10f) -add_subdirectory(AT10) -add_subdirectory(GX40) - -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 - Gimabl_GX40 -) - -target_include_directories(AMOV_Gimbal - PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) - diff --git a/gimbal_ctrl/driver/src/FIFO/CMakeLists.txt b/gimbal_ctrl/driver/src/FIFO/CMakeLists.txt deleted file mode 100755 index 2357221..0000000 --- a/gimbal_ctrl/driver/src/FIFO/CMakeLists.txt +++ /dev/null @@ -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} -) \ No newline at end of file diff --git a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp index 87585a0..91d0c7f 100755 --- a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp +++ b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp @@ -3,8 +3,8 @@ * @Author : Aiyangsky * @Date : 2022-08-26 21:42:10 * @LastEditors: L LC @amov - * @LastEditTime: 2023-07-21 16:10:16 - * @FilePath: /gimbal-sdk-multi-platform/src/FIFO/Ring_Fifo.cpp + * @LastEditTime: 2023-11-28 11:47:34 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp */ #include diff --git a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h index 96c3e63..d470988 100755 --- a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h +++ b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h @@ -3,8 +3,8 @@ * @Author : Aiyangsky * @Date : 2022-08-26 21:42:02 * @LastEditors: L LC @amov - * @LastEditTime: 2023-08-16 21:22:46 - * @FilePath: /gimbal-sdk-multi-platform/src/FIFO/Ring_Fifo.h + * @LastEditTime: 2023-11-28 11:47:39 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h */ #ifndef RING_FIFO_H diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h index a974124..55dd04a 100755 --- a/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h +++ b/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2022-10-28 14:10:02 - * @FilePath: \amov-gimbal-sdk\src\G1\g1_gimbal_crc32.h + * @LastEditTime: 2023-11-28 11:47:02 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h */ #ifndef G1_GIMBAL_CRC32_H #define G1_GIMBAL_CRC32_H diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp index 7484938..75ce4d4 100755 --- a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp +++ b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2023-09-07 11:01:25 - * @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_driver.cpp + * @LastEditTime: 2023-11-28 11:47:07 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp */ #include "g1_gimbal_driver.h" #include "g1_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h index c293fd2..5346b59 100755 --- a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h +++ b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-28 12:24:21 * @LastEditors: L LC @amov - * @LastEditTime: 2023-09-07 02:31:19 - * @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_driver.h + * @LastEditTime: 2023-11-28 11:47:12 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h */ #include "../amov_gimbal.h" #include "../amov_gimbal_private.h" diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp index 590dbcd..05d5d8c 100755 --- a/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp +++ b/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-03-02 10:00:52 * @LastEditors: L LC @amov - * @LastEditTime: 2023-09-07 10:50:30 - * @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_funtion.cpp + * @LastEditTime: 2023-11-28 11:47:19 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp */ #include "g1_gimbal_driver.h" #include "g1_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h index f551a41..43b0a02 100755 --- a/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:07 * @LastEditors: L LC @amov - * @LastEditTime: 2023-09-07 10:45:13 - * @FilePath: /gimbal-sdk-multi-platform/src/G1/g1_gimbal_struct.h + * @LastEditTime: 2023-11-28 11:47:24 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h */ #ifndef G1_GIMBAL_STRUCT_H #define G1_GIMBAL_STRUCT_H diff --git a/gimbal_ctrl/driver/src/GX40/CMakeLists.txt b/gimbal_ctrl/driver/src/GX40/CMakeLists.txt deleted file mode 100755 index 849562c..0000000 --- a/gimbal_ctrl/driver/src/GX40/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -add_library(Gimabl_GX40) - -file(GLOB LIB_FILES ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp) - -target_sources(Gimabl_GX40 - PUBLIC - ${LIB_FILES} -) - -target_link_libraries(Gimabl_GX40 - PUBLIC - FIFO -) - -target_include_directories(Gimabl_GX40 - PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} -) \ No newline at end of file diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h index f3bd6c1..c26b45c 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-10-20 16:33:07 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-01 17:03:16 - * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_crc16.h + * @LastEditTime: 2023-11-28 11:46:51 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_crc16.h */ #ifndef GX40_GIMBAL_CRC16_H #define GX40_GIMBAL_CRC16_H diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp index 7c09a02..019135a 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-10-20 16:08:17 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-16 17:23:38 - * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_driver.cpp + * @LastEditTime: 2023-11-28 11:46:45 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.cpp */ #include #include "GX40_gimbal_driver.h" diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h index a3df9ba..d0b63a3 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h @@ -4,8 +4,8 @@ * @Author: L LC @amov * @Date: 2023-10-20 16:08:13 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-16 17:23:27 - * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_driver.h + * @LastEditTime: 2023-11-28 11:46:35 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_driver.h */ #include "../amov_gimbal.h" #include "../amov_gimbal_private.h" diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp index ae33e6a..e286ae0 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-11-02 17:50:26 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-16 17:23:07 - * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_funtion.cpp + * @LastEditTime: 2023-11-28 11:46:28 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_funtion.cpp */ #include #include "GX40_gimbal_driver.h" diff --git a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h index 2447da2..b5d65ce 100644 --- a/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-10-20 16:08:13 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-16 17:27:05 - * @FilePath: /gimbal-sdk-multi-platform/src/GX40/GX40_gimbal_struct.h + * @LastEditTime: 2023-11-28 11:46:22 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/GX40/GX40_gimbal_struct.h */ #ifndef GX40_GIMBAL_STRUCT_H #define GX40_GIMBAL_STRUCT_H diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h index 709b2d8..7273d2b 100755 --- a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h +++ b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2023-03-23 17:24:23 - * @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_crc32.h + * @LastEditTime: 2023-11-28 11:45:25 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h */ #ifndef Q10F_GIMBAL_CRC32_H #define Q10F_GIMBAL_CRC32_H diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp index 4262cf2..4b7d27f 100755 --- a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp +++ b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:06 * @LastEditors: L LC @amov - * @LastEditTime: 2023-07-24 12:03:44 - * @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_driver.cpp + * @LastEditTime: 2023-11-28 11:45:31 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp */ #include "Q10f_gimbal_driver.h" #include "Q10f_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h index 38a849a..a480f5b 100755 --- a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h +++ b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-28 12:24:21 * @LastEditors: L LC @amov - * @LastEditTime: 2023-03-28 17:01:00 - * @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_driver.h + * @LastEditTime: 2023-11-28 11:45:36 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h */ #include "../amov_gimbal.h" #include "../amov_gimbal_private.h" diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp index 4406d07..6f2b7ab 100755 --- a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp +++ b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-03-02 10:00:52 * @LastEditors: L LC @amov - * @LastEditTime: 2023-07-24 14:22:57 - * @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_funtion.cpp + * @LastEditTime: 2023-11-28 11:45:41 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp */ #include "Q10f_gimbal_driver.h" #include "Q10f_gimbal_crc32.h" diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h index fc701d4..9668b4b 100755 --- a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:10:07 * @LastEditors: L LC @amov - * @LastEditTime: 2023-07-24 11:51:59 - * @FilePath: /gimbal-sdk-multi-platform/src/Q10f/Q10f_gimbal_struct.h + * @LastEditTime: 2023-11-28 11:45:46 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h */ #ifndef Q10F_GIMBAL_STRUCT_H #define Q10F_GIMBAL_STRUCT_H diff --git a/gimbal_ctrl/driver/src/amov_gimbal.cpp b/gimbal_ctrl/driver/src/amov_gimbal.cpp index af39154..36129df 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal.cpp +++ b/gimbal_ctrl/driver/src/amov_gimbal.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-28 11:54:11 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-16 17:27:28 - * @FilePath: gimbal_ctrl/driver/src/amov_gimbal.cpp + * @LastEditTime: 2023-11-28 11:44:37 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal.cpp */ #include "amov_gimbal_private.h" diff --git a/gimbal_ctrl/driver/src/amov_gimbal.h b/gimbal_ctrl/driver/src/amov_gimbal.h index 5b74ee9..cb203c6 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal.h +++ b/gimbal_ctrl/driver/src/amov_gimbal.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-27 18:34:26 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-14 13:57:33 - * @FilePath: gimbal_ctrl/driver/src/amov_gimbal.h + * @LastEditTime: 2023-11-28 11:44:44 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal.h */ #ifndef AMOV_GIMBAL_H diff --git a/gimbal_ctrl/driver/src/amov_gimbal_private.h b/gimbal_ctrl/driver/src/amov_gimbal_private.h index 2e354c2..1b97255 100644 --- a/gimbal_ctrl/driver/src/amov_gimbal_private.h +++ b/gimbal_ctrl/driver/src/amov_gimbal_private.h @@ -3,8 +3,8 @@ * @Author : Aiyangsky * @Date : 2023-05-13 10:39:20 * @LastEditors: L LC @amov - * @LastEditTime: 2023-11-14 10:35:56 - * @FilePath: gimbal_ctrl/driver/src/amov_gimbal_private.h + * @LastEditTime: 2023-11-28 11:45:18 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_private.h */ #ifndef __AMOV_GIMABL_PRIVATE_H #define __AMOV_GIMABL_PRIVATE_H diff --git a/gimbal_ctrl/driver/src/amov_gimbal_struct.h b/gimbal_ctrl/driver/src/amov_gimbal_struct.h index e68f4d2..991440a 100755 --- a/gimbal_ctrl/driver/src/amov_gimbal_struct.h +++ b/gimbal_ctrl/driver/src/amov_gimbal_struct.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2022-10-31 11:56:43 * @LastEditors: L LC @amov - * @LastEditTime: 2023-10-23 18:05:59 - * @FilePath: gimbal_ctrl/driver/src/amov_gimbal_struct.h + * @LastEditTime: 2023-11-28 11:44:30 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_gimbal_struct.h */ #include diff --git a/gimbal_ctrl/driver/src/amov_tool.h b/gimbal_ctrl/driver/src/amov_tool.h index 82c6536..0e7ae9d 100644 --- a/gimbal_ctrl/driver/src/amov_tool.h +++ b/gimbal_ctrl/driver/src/amov_tool.h @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-07-31 18:30:33 * @LastEditors: L LC @amov - * @LastEditTime: 2023-07-31 18:55:18 - * @FilePath: gimbal_ctrl/driver/src/amov_tool.h + * @LastEditTime: 2023-11-28 11:44:49 + * @FilePath: /SpireCV/gimbal_ctrl/driver/src/amov_tool.h */ namespace amovGimbalTools diff --git a/gimbal_ctrl/sv_gimbal.cpp b/gimbal_ctrl/sv_gimbal.cpp index 43e941d..17edcd1 100644 --- a/gimbal_ctrl/sv_gimbal.cpp +++ b/gimbal_ctrl/sv_gimbal.cpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-04-12 09:12:52 * @LastEditors: L LC @amov - * @LastEditTime: 2023-04-18 11:37:42 - * @FilePath: /spirecv-gimbal-sdk/gimbal_ctrl/sv_gimbal.cpp + * @LastEditTime: 2023-11-28 11:43:39 + * @FilePath: /SpireCV/gimbal_ctrl/sv_gimbal.cpp */ #include "amov_gimbal.h" #include "amov_gimbal_struct.h" diff --git a/gimbal_ctrl/sv_gimbal_io.hpp b/gimbal_ctrl/sv_gimbal_io.hpp index 9781e48..e74d1bc 100644 --- a/gimbal_ctrl/sv_gimbal_io.hpp +++ b/gimbal_ctrl/sv_gimbal_io.hpp @@ -3,8 +3,8 @@ * @Author: L LC @amov * @Date: 2023-04-12 12:22:09 * @LastEditors: L LC @amov - * @LastEditTime: 2023-04-13 10:17:21 - * @FilePath: /spirecv-gimbal-sdk/gimbal_ctrl/sv_gimbal_io.hpp + * @LastEditTime: 2023-11-28 11:43:49 + * @FilePath: /SpireCV/gimbal_ctrl/sv_gimbal_io.hpp */ #ifndef __SV_GIMABL_IO_H #define __SV_GIMABL_IO_H From 831eab51974d42479bdd4fbeb23f32ae7a48b8d5 Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:40:13 +0000 Subject: [PATCH 4/9] update video_io/sv_video_input.cpp. Signed-off-by: jario-jin --- video_io/sv_video_input.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/video_io/sv_video_input.cpp b/video_io/sv_video_input.cpp index 01c3e04..2db1c8d 100644 --- a/video_io/sv_video_input.cpp +++ b/video_io/sv_video_input.cpp @@ -2,17 +2,16 @@ #include #include -namespace sv -{ +namespace sv { Camera::Camera() { } + Camera::~Camera() { } - void Camera::openImpl() { if (this->_type == CameraType::WEBCAM || this->_type == CameraType::V4L2CAM) From 4ec37d79e399909b2a6ba2dd9ee0087c4161cf50 Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:43:19 +0000 Subject: [PATCH 5/9] update samples/demo/gimbal_udp_detection_info_sender.cpp. Signed-off-by: jario-jin --- samples/demo/gimbal_udp_detection_info_sender.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/samples/demo/gimbal_udp_detection_info_sender.cpp b/samples/demo/gimbal_udp_detection_info_sender.cpp index b7efabb..f9ee0a8 100644 --- a/samples/demo/gimbal_udp_detection_info_sender.cpp +++ b/samples/demo/gimbal_udp_detection_info_sender.cpp @@ -55,7 +55,7 @@ int main(int argc, char *argv[]) cap.setIp("192.168.2.64"); // 设置获取画面分辨率为720P cap.setWH(1280, 720); - // // 设置视频帧率为30帧 + // 设置视频帧率为30帧 cap.setFps(30); // 开启相机 cap.open(sv::CameraType::G1); @@ -80,7 +80,7 @@ int main(int argc, char *argv[]) // 读取一帧图像到img cap.read(img); - std::cout << img.type() << std::endl; + // std::cout << img.type() << std::endl; // 执行Aruco二维码检测 ad.detect(img, tgts); From 2985661e90172e6305ac086e360d01aeeecb2345 Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:45:18 +0000 Subject: [PATCH 6/9] update samples/demo/detection_with_clicked_tracking.cpp. Signed-off-by: jario-jin --- samples/demo/detection_with_clicked_tracking.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/samples/demo/detection_with_clicked_tracking.cpp b/samples/demo/detection_with_clicked_tracking.cpp index 3bd5a07..fcfd73e 100644 --- a/samples/demo/detection_with_clicked_tracking.cpp +++ b/samples/demo/detection_with_clicked_tracking.cpp @@ -50,15 +50,12 @@ int main(int argc, char *argv[]) { // 打开摄像头 - // sv::Camera cap; + sv::Camera cap; // cap.setWH(640, 480); // cap.setFps(30); - // cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0 - // cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4"); - // 实例化OpenCV的Mat类,用于内存单帧图像 + cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0 - cv::VideoCapture cap; - cap.open("/dev/video0"); + // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; int frame_id = 0; From dbd60027efd6d5ec5199ecf333e8893bd85cb301 Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:47:00 +0000 Subject: [PATCH 7/9] update scripts/x86-cuda/x86-opencv470-cuda-install.sh. Signed-off-by: jario-jin --- scripts/x86-cuda/x86-opencv470-cuda-install.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/scripts/x86-cuda/x86-opencv470-cuda-install.sh b/scripts/x86-cuda/x86-opencv470-cuda-install.sh index 8535a11..c44e718 100755 --- a/scripts/x86-cuda/x86-opencv470-cuda-install.sh +++ b/scripts/x86-cuda/x86-opencv470-cuda-install.sh @@ -1,5 +1,6 @@ #!/bin/sh + wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip @@ -59,7 +60,7 @@ cmake -D CMAKE_BUILD_TYPE=Release \ -D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda \ -D OPENCV_ENABLE_NONFREE=ON \ -D CMAKE_INSTALL_PREFIX=/usr/local \ - -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. + -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. make -j2 sudo make install From 315c63a472f0d688f585493fd1cd461490ea584a Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:48:31 +0000 Subject: [PATCH 8/9] update scripts/x86-cuda/x86-opencv470-install.sh. Signed-off-by: jario-jin --- scripts/x86-cuda/x86-opencv470-install.sh | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/scripts/x86-cuda/x86-opencv470-install.sh b/scripts/x86-cuda/x86-opencv470-install.sh index e065991..414164b 100755 --- a/scripts/x86-cuda/x86-opencv470-install.sh +++ b/scripts/x86-cuda/x86-opencv470-install.sh @@ -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 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 ..." @@ -52,16 +56,11 @@ cp -r ~/opencv_build/opencv_cache_x86-4.7.0/* ~/opencv_build/opencv-4.7.0/.cache mkdir build cd build -sudo apt-get 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 - cmake -D CMAKE_BUILD_TYPE=Release \ -D WITH_CUDA=OFF \ -D OPENCV_ENABLE_NONFREE=ON \ -D CMAKE_INSTALL_PREFIX=/usr/local \ - -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. + -D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules .. make -j2 sudo make install From 6c417adc340232e323bf6200658c29d5c4d3b980 Mon Sep 17 00:00:00 2001 From: jario-jin Date: Thu, 30 Nov 2023 00:50:03 +0000 Subject: [PATCH 9/9] update samples/demo/detection_with_clicked_tracking.cpp. Signed-off-by: jario-jin --- samples/demo/detection_with_clicked_tracking.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/samples/demo/detection_with_clicked_tracking.cpp b/samples/demo/detection_with_clicked_tracking.cpp index fcfd73e..7a779a4 100644 --- a/samples/demo/detection_with_clicked_tracking.cpp +++ b/samples/demo/detection_with_clicked_tracking.cpp @@ -2,8 +2,6 @@ #include // 包含SpireCV SDK头文件 #include -#include -#include using namespace std; @@ -57,7 +55,6 @@ int main(int argc, char *argv[]) { // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; - int frame_id = 0; while (1) {