wangyingjie před 2 měsíci
rodič
revize
bddd683a70

+ 7 - 2
readme.md

@@ -2,7 +2,7 @@
  * @Author: wangyingjie 2778809626@qq.com
  * @Date: 2025-05-22 17:32:41
  * @LastEditors: wangyingjie 2778809626@qq.com
- * @LastEditTime: 2025-05-22 17:34:38
+ * @LastEditTime: 2025-06-20 17:58:26
  * @FilePath: \undefinedd:\7_work\1_nzzn\2_code\6_drive\Drive\readme.md
  * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
 -->
@@ -11,4 +11,9 @@
 
 ## g29_ros2_feedback_drive
 
-该项目是罗技G29手柄的ros2驱动程序,用于将手柄的输入转换为ROS2消息,并发布到ROS2话题中。
+该项目是罗技G29手柄的ros2驱动程序,用于将手柄的输入转换为ROS2消息,并发布到ROS2话题中。
+
+
+## sr71_drive
+
+该项目是 纳雷科技 SR71 毫米波雷达的 c++ 驱动程序,将目标数据解析出来 

+ 151 - 0
sr71_drive/.clang-format

@@ -0,0 +1,151 @@
+---
+Language:        Cpp
+# BasedOnStyle:  Google
+AccessModifierOffset: -2
+AlignAfterOpenBracket: Align
+AlignConsecutiveAssignments: false
+AlignConsecutiveDeclarations: false
+AlignEscapedNewlines: Left
+AlignOperands:   true
+AlignTrailingComments: true
+AllowAllParametersOfDeclarationOnNextLine: false
+AllowShortBlocksOnASingleLine: false
+AllowShortCaseLabelsOnASingleLine: false
+AllowShortFunctionsOnASingleLine: None
+AllowShortIfStatementsOnASingleLine: false
+AllowShortLoopsOnASingleLine: false
+AlwaysBreakAfterDefinitionReturnType: None
+AlwaysBreakAfterReturnType: None
+AlwaysBreakBeforeMultilineStrings: true
+AlwaysBreakTemplateDeclarations: true
+BinPackArguments: false
+BinPackParameters: false 
+BraceWrapping:   
+  AfterClass:      true
+  AfterControlStatement: Always
+  AfterEnum:       true
+  AfterFunction:   true
+  AfterNamespace:  true
+  AfterObjCDeclaration: false
+  AfterStruct:     true
+  AfterUnion:      true
+  AfterExternBlock: true
+  BeforeCatch:     true
+  BeforeElse:      true
+  IndentBraces:    false
+  SplitEmptyFunction: true
+  SplitEmptyRecord: true
+  SplitEmptyNamespace: true
+  AfterCaseLabel: true
+BreakBeforeBinaryOperators: None
+BreakBeforeBraces: Custom
+BreakBeforeInheritanceComma: false
+BreakInheritanceList: BeforeColon
+BreakBeforeTernaryOperators: true
+BreakConstructorInitializersBeforeComma: false
+BreakConstructorInitializers: BeforeColon
+BreakAfterJavaFieldAnnotations: false
+BreakStringLiterals: true
+ColumnLimit:     256
+CommentPragmas:  '^ IWYU pragma:'
+CompactNamespaces: false
+ConstructorInitializerAllOnOneLineOrOnePerLine: true
+ConstructorInitializerIndentWidth: 4
+ContinuationIndentWidth: 4
+Cpp11BracedListStyle: true
+DerivePointerAlignment: true
+DisableFormat:   false
+FixNamespaceComments: true
+ForEachMacros:   
+  - foreach
+  - Q_FOREACH
+  - BOOST_FOREACH
+IncludeBlocks:   Preserve
+IncludeCategories: 
+  - Regex:           '^<ext/.*\.h>'
+    Priority:        2
+  - Regex:           '^<.*\.h>'
+    Priority:        1
+  - Regex:           '^<.*'
+    Priority:        2
+  - Regex:           '.*'
+    Priority:        3
+IncludeIsMainRegex: '([-_](test|unittest))?$'
+IndentCaseLabels: true
+IndentPPDirectives: None
+IndentWidth:    4 
+IndentWrappedFunctionNames: false
+JavaScriptQuotes: Leave
+JavaScriptWrapImports: true
+KeepEmptyLinesAtTheStartOfBlocks: false
+MacroBlockBegin: ''
+MacroBlockEnd:   ''
+MaxEmptyLinesToKeep: 1
+NamespaceIndentation: None
+ObjCBinPackProtocolList: Never
+ObjCBlockIndentWidth: 2
+ObjCSpaceAfterProperty: false
+ObjCSpaceBeforeProtocolList: true
+PenaltyBreakAssignment: 2
+PenaltyBreakBeforeFirstCallParameter: 100
+PenaltyBreakComment: 300
+PenaltyBreakFirstLessLess: 120
+PenaltyBreakString: 1000
+PenaltyBreakTemplateDeclaration: 10
+PenaltyExcessCharacter: 1000000
+PenaltyReturnTypeOnItsOwnLine: 2000
+PointerAlignment: Left
+RawStringFormats: 
+  - Language:        Cpp
+    Delimiters:      
+      - cc
+      - CC
+      - cpp
+      - Cpp
+      - CPP
+      - 'c++'
+      - 'C++'
+    CanonicalDelimiter: ''
+    BasedOnStyle:    google
+  - Language:        TextProto
+    Delimiters:      
+      - pb
+      - PB
+      - proto
+      - PROTO
+    EnclosingFunctions: 
+      - EqualsProto
+      - EquivToProto
+      - PARSE_PARTIAL_TEXT_PROTO
+      - PARSE_TEST_PROTO
+      - PARSE_TEXT_PROTO
+      - ParseTextOrDie
+      - ParseTextProtoOrDie
+    CanonicalDelimiter: ''
+    BasedOnStyle:    google
+ReflowComments:  true
+SortIncludes:    false
+SortUsingDeclarations: true
+SpaceAfterCStyleCast: false
+SpaceAfterTemplateKeyword: true
+SpaceBeforeAssignmentOperators: true
+SpaceBeforeCpp11BracedList: false
+SpaceBeforeCtorInitializerColon: true
+SpaceBeforeInheritanceColon: true
+SpaceBeforeParens: ControlStatements
+SpaceBeforeRangeBasedForLoopColon: true
+SpaceInEmptyParentheses: false
+SpacesBeforeTrailingComments: 2
+SpacesInAngles:  false
+SpacesInContainerLiterals: true
+SpacesInCStyleCastParentheses: false
+SpacesInParentheses: false
+SpacesInSquareBrackets: false
+Standard:        Auto
+StatementMacros: 
+  - Q_UNUSED
+  - QT_REQUIRE_VERSION
+TabWidth:        8
+UseTab:          Never
+...
+

+ 56 - 0
sr71_drive/CMakeLists.txt

@@ -0,0 +1,56 @@
+cmake_minimum_required(VERSION 3.15)
+
+project(example_project)
+
+message("============== 构建项目开始 ==============")
+
+# ------- all_in_one beg -------
+
+# 判断当前目录是否为 cmake的根目录,如果不是,则是被其他项目引用的,不需要编译测试,工具模块
+message("AO当前文件根目录 (CMAKE_CURRENT_SOURCE_DIR) ${CMAKE_CURRENT_SOURCE_DIR}")
+message("AO当前项目根目录 (CMAKE_SOURCE_DIR) ${CMAKE_SOURCE_DIR}")
+
+# 当前文件路径
+set(AO_FILE_ROOT "${CMAKE_CURRENT_SOURCE_DIR}")
+# 项目根CMakeLists.txt文件路径
+set(AO_PROJ_ROOT "${CMAKE_SOURCE_DIR}")
+set(CMAKE_MODULE_PATH "${AO_FILE_ROOT}/cmake;${CMAKE_MODULE_PATH}")
+if("${AO_FILE_ROOT}" STREQUAL "${AO_PROJ_ROOT}")
+	set(BUILD_AS_PROJ TRUE)
+	message("作为单个工程编译")
+	include(${AO_PROJ_ROOT}/cmake/ThirdSupport.cmake)
+else ()
+	set(BUILD_AS_LIB TRUE)
+	message("作为嵌入库编译")
+endif()
+
+include(ThirdSupport)
+include(all_in_one)
+
+# 设置默认程序根目录,程序中所有路径均参照此路径,方便调试和发布
+if(DEBUG_MODE)
+    set(DEFAULT_CONFIG_DIR "${CMAKE_SOURCE_DIR}/config")
+    add_definitions("-DDEFAULT_ROOT_DIR=\"${CMAKE_SOURCE_DIR}\"")
+    add_definitions("-DDEFAULT_CONFIG_DIR=\"${DEFAULT_CONFIG_DIR}\"")
+else()
+    add_definitions("-DDEFAULT_ROOT_DIR=\"./\"")
+    add_definitions("-DDEFAULT_CONFIG_DIR=\"./config\"")
+endif()
+message("当前根目录: ${DEFAULT_ROOT_DIR}")
+message("配置文件目录: ${DEFAULT_CONFIG_DIR}")
+
+include_directories(${CMAKE_CURRENT_SOURCE_DIR}/core)
+
+# 添加目录
+add_subdirectory(core)  # core代码
+add_subdirectory(src)   # 主函数
+
+
+
+
+
+
+
+
+
+

+ 27 - 0
sr71_drive/CMakeSettings.json

@@ -0,0 +1,27 @@
+{
+  "configurations": [
+    {
+      "name": "x64-Debug",
+      "generator": "Ninja",
+      "configurationType": "Debug",
+      "inheritEnvironments": [ "msvc_x64_x64" ],
+      "buildRoot": "${projectDir}\\out\\build\\${name}",
+      "installRoot": "${projectDir}\\out\\install\\${name}",
+      "cmakeCommandArgs": "",
+      "buildCommandArgs": "",
+      "ctestCommandArgs": ""
+    },
+    {
+      "name": "x64-Release",
+      "generator": "Ninja",
+      "configurationType": "Release",
+      "buildRoot": "${projectDir}\\out\\build\\${name}",
+      "installRoot": "${projectDir}\\out\\install\\${name}",
+      "cmakeCommandArgs": "",
+      "buildCommandArgs": "",
+      "ctestCommandArgs": "",
+      "inheritEnvironments": [ "msvc_x64_x64" ],
+      "variables": []
+    }
+  ]
+}

+ 16 - 0
sr71_drive/README.md

@@ -0,0 +1,16 @@
+<!--
+ * @Author: yingjie_wang 2778809626@qq.com
+ * @Date: 2024-01-03 13:44:31
+ * @LastEditors: wangyingjie 2778809626@qq.com
+ * @LastEditTime: 2025-06-20 13:35:43
+ * @FilePath: \projectd:\1_wangyingjie\learn\github_project\1_cmake_template\project_template\README.md
+ * @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
+-->
+# project_template
+
+纳雷科技 SR71 雷达数据接收
+
+cmake 参数 -DCMAKE_TOOLCHAIN_FILE=~/env/vcpkg/scripts/buildsystems/vcpkg.cmake
+
+lsusb
+sudo chmod 777 /dev/bus/usb/001/015

+ 6 - 0
sr71_drive/cmake/ThirdSupport.cmake

@@ -0,0 +1,6 @@
+# 第三方库支持
+
+set(ENABLE_GDAL YES) # gdal支持
+set(ENABLE_PAHO_MQTT YES) # mqtt支持
+
+

+ 42 - 0
sr71_drive/cmake/all_in_one.cmake

@@ -0,0 +1,42 @@
+
+message("============== all in one Module ==============")
+
+# 添加第三方依赖包
+include(FetchContent)
+# FetchContent_MakeAvailable was not added until CMake 3.14
+if(${CMAKE_VERSION} VERSION_LESS 3.14)
+    include(add_FetchContent_MakeAvailable.cmake)
+endif()
+
+# 设置all_in_one的下载目录
+if("${ALL_IN_ONE_FETCH_ROOT}" STREQUAL "")
+    set(ALL_IN_ONE_FETCH_ROOT ${CMAKE_SOURCE_DIR})
+endif()
+
+
+# 指定版本
+set(SILLY_UTIL_TAG  master)  
+set(ALL_IN_ONE_GIT_URL  "https://gitee.com/master-turtle/all_in_one.git")  
+
+
+FetchContent_Declare(
+  all_in_one
+  GIT_REPOSITORY    ${ALL_IN_ONE_GIT_URL}
+  SOURCE_DIR        ${ALL_IN_ONE_FETCH_ROOT}/all_in_one
+)
+
+FetchContent_MakeAvailable(all_in_one)
+
+# 下载完成后 拷贝检测环境的.cmake文件
+IF(NOT EXISTS "${CMAKE_SOURCE_DIR}/")
+    FILE(MAKE_DIRECTORY "${CMAKE_SOURCE_DIR}/")
+ENDIF()
+
+execute_process(COMMAND ${CMAKE_COMMAND} -E  copy "${ALL_IN_ONE_FETCH_ROOT}/all_in_one/.clang-format" "${CMAKE_SOURCE_DIR}/.clang-format")
+
+set(CMAKE_MODULE_PATH "${ALL_IN_ONE_FETCH_ROOT}/all_in_one/cmake;${CMAKE_MODULE_PATH}")
+message(STATUS "cmake 目录: ${CMAKE_MODULE_PATH}")
+include(EnvModule)
+include(OSEndianModule)
+
+include_directories("${ALL_IN_ONE_FETCH_ROOT}/all_in_one/core")

+ 6 - 0
sr71_drive/config/config.json

@@ -0,0 +1,6 @@
+{
+  "DevType": 3,
+  "DevIdx": 0,
+  "ChMask": 1,
+  "Baud": "0x1c00"
+}

+ 12 - 0
sr71_drive/config/radar_config.txt

@@ -0,0 +1,12 @@
+# 雷达配置
+ReceiverType=CAN
+
+# CAN配置
+DevType=3
+DevIdx=0
+ChMask=1
+Baud=0x1c00
+
+# TCP配置
+TCP_IP=192.168.1.100
+TCP_Port=5000

+ 28 - 0
sr71_drive/core/CMakeLists.txt

@@ -0,0 +1,28 @@
+cmake_minimum_required (VERSION 3.15)
+
+project(core_lib CXX)
+foreach(dirname ${CMAKE_CURRENT_SOURCE_DIR})
+    file(GLOB_RECURSE SRC RELATIVE ${CMAKE_CURRENT_SOURCE_DIR}
+            "${dirname}/*.h"
+            "${dirname}/*.hpp"
+            "${dirname}/*.c"
+            "${dirname}/*.cpp"
+            )
+endforeach()
+
+add_library(${PROJECT_NAME} STATIC ${SRC})
+
+find_package(Threads REQUIRED)
+target_link_libraries(${PROJECT_NAME} PUBLIC Threads::Threads)
+target_link_libraries(${PROJECT_NAME} PUBLIC  usbcan)
+
+#find_package(jsoncpp CONFIG REQUIRED)
+#target_link_libraries(${PROJECT_NAME} PUBLIC JsonCpp::JsonCpp)
+
+find_package(PkgConfig REQUIRED)
+pkg_check_modules(libusb REQUIRED IMPORTED_TARGET libusb-1.0)
+target_link_libraries(${PROJECT_NAME} PUBLIC PkgConfig::libusb)
+
+
+
+target_link_libraries(${PROJECT_NAME} PUBLIC MultiTool)

+ 8 - 0
sr71_drive/core/config/module_a_config.cpp

@@ -0,0 +1,8 @@
+//
+// Created by dell on 2024/7/17.
+//
+
+
+#include "module_a_config.h"
+
+// 配置

+ 27 - 0
sr71_drive/core/config/module_a_config.h

@@ -0,0 +1,27 @@
+
+#ifndef MODULE_A_CONFIG_H
+#define MODULE_A_CONFIG_H
+
+#include "project_marco.h"
+
+/// <summary>
+/// 配置模块A
+/// </summary>
+class module_a_config : public studio_singleton<module_a_config>
+{
+  public:
+    bool read_config(const std::string& fpath)
+    {
+        bool status = false;
+        if (!std::filesystem::exists(std::filesystem::path(fpath)))
+        {
+            std::cout << "config file not exist" << std::endl;
+            return status;
+        }
+
+        status = true;
+        return status;
+    }
+};
+
+#endif  // MODULE_A_CONFIG_H

+ 138 - 0
sr71_drive/core/controlcan.h

@@ -0,0 +1,138 @@
+#ifndef CONTROLCAN_H
+#define CONTROLCAN_H
+
+//接口卡类型定义
+#define VCI_PCI5121		1
+#define VCI_PCI9810		2
+#define VCI_USBCAN1		3
+#define VCI_USBCAN2		4
+#define VCI_PCI9820		5
+#define VCI_CAN232		6
+#define VCI_PCI5110		7
+#define VCI_CANLite		8
+#define VCI_ISA9620		9
+#define VCI_ISA5420		10
+
+//CAN错误码
+#define	ERR_CAN_OVERFLOW			0x0001	//CAN控制器内部FIFO溢出
+#define	ERR_CAN_ERRALARM			0x0002	//CAN控制器错误报警
+#define	ERR_CAN_PASSIVE				0x0004	//CAN控制器消极错误
+#define	ERR_CAN_LOSE				0x0008	//CAN控制器仲裁丢失
+#define	ERR_CAN_BUSERR				0x0010	//CAN控制器总线错误
+
+//通用错误码
+#define	ERR_DEVICEOPENED			0x0100	//设备已经打开
+#define	ERR_DEVICEOPEN				0x0200	//打开设备错误
+#define	ERR_DEVICENOTOPEN			0x0400	//设备没有打开
+#define	ERR_BUFFEROVERFLOW			0x0800	//缓冲区溢出
+#define	ERR_DEVICENOTEXIST			0x1000	//此设备不存在
+#define	ERR_LOADKERNELDLL			0x2000	//装载动态库失败
+#define ERR_CMDFAILED				0x4000	//执行命令失败错误码
+#define	ERR_BUFFERCREATE			0x8000	//内存不足
+
+
+//函数调用返回状态值
+#define	STATUS_OK					1
+#define STATUS_ERR					0
+	
+#define USHORT unsigned short int
+#define BYTE unsigned char
+#define CHAR char
+#define UCHAR unsigned char
+#define UINT unsigned int
+#define DWORD unsigned int
+#define PVOID void*
+#define ULONG unsigned int
+#define INT int
+#define UINT32 UINT
+#define LPVOID void*
+#define BOOL BYTE
+#define TRUE 1
+#define FALSE 0
+
+
+//1.ZLGCAN系列接口卡信息的数据类型。
+typedef  struct  _VCI_BOARD_INFO{
+		USHORT	hw_Version;
+		USHORT	fw_Version;
+		USHORT	dr_Version;
+		USHORT	in_Version;
+		USHORT	irq_Num;
+		BYTE	can_Num;
+		CHAR	str_Serial_Num[20];
+		CHAR	str_hw_Type[40];
+		USHORT	Reserved[4];
+} VCI_BOARD_INFO,*PVCI_BOARD_INFO; 
+
+//2.定义CAN信息帧的数据类型。
+typedef  struct  _VCI_CAN_OBJ{
+	UINT	ID;
+	UINT	TimeStamp;
+	BYTE	TimeFlag;
+	BYTE	SendType;
+	BYTE	RemoteFlag;//是否是远程帧
+	BYTE	ExternFlag;//是否是扩展帧
+	BYTE	DataLen;
+	BYTE	Data[8];
+	BYTE	Reserved[3];
+}VCI_CAN_OBJ,*PVCI_CAN_OBJ;
+
+//3.定义CAN控制器状态的数据类型。
+typedef struct _VCI_CAN_STATUS{
+	UCHAR	ErrInterrupt;
+	UCHAR	regMode;
+	UCHAR	regStatus;
+	UCHAR	regALCapture;
+	UCHAR	regECCapture; 
+	UCHAR	regEWLimit;
+	UCHAR	regRECounter; 
+	UCHAR	regTECounter;
+	DWORD	Reserved;
+}VCI_CAN_STATUS,*PVCI_CAN_STATUS;
+
+//4.定义错误信息的数据类型。
+typedef struct _ERR_INFO{
+		UINT	ErrCode;
+		BYTE	Passive_ErrData[3];
+		BYTE	ArLost_ErrData;
+} VCI_ERR_INFO,*PVCI_ERR_INFO;
+
+//5.定义初始化CAN的数据类型
+typedef struct _INIT_CONFIG{
+	DWORD	AccCode;
+	DWORD	AccMask;
+	DWORD	Reserved;
+	UCHAR	Filter;
+	UCHAR	Timing0;	
+	UCHAR	Timing1;	
+	UCHAR	Mode;
+}VCI_INIT_CONFIG,*PVCI_INIT_CONFIG;
+
+#ifdef __cplusplus
+#define EXTERN_C  extern "C"
+#else
+#define EXTERN_C
+#endif
+
+EXTERN_C DWORD VCI_OpenDevice(DWORD DeviceType,DWORD DeviceInd,DWORD Reserved);
+EXTERN_C DWORD VCI_CloseDevice(DWORD DeviceType,DWORD DeviceInd);
+EXTERN_C DWORD VCI_InitCAN(DWORD DeviceType, DWORD DeviceInd, DWORD CANInd, PVCI_INIT_CONFIG pInitConfig);
+
+EXTERN_C DWORD VCI_ReadBoardInfo(DWORD DeviceType,DWORD DeviceInd,PVCI_BOARD_INFO pInfo);
+EXTERN_C DWORD VCI_ReadErrInfo(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_ERR_INFO pErrInfo);
+EXTERN_C DWORD VCI_ReadCANStatus(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_STATUS pCANStatus);
+
+EXTERN_C DWORD VCI_GetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+EXTERN_C DWORD VCI_SetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+
+EXTERN_C ULONG VCI_GetReceiveNum(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+EXTERN_C DWORD VCI_ClearBuffer(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+EXTERN_C DWORD VCI_StartCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+EXTERN_C DWORD VCI_ResetCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+EXTERN_C ULONG VCI_Transmit(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pSend,UINT Len);
+EXTERN_C ULONG VCI_Receive(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pReceive,UINT Len,INT WaitTime);
+
+#endif
+

+ 16 - 0
sr71_drive/core/project_marco.h

@@ -0,0 +1,16 @@
+//
+// Created by dell on 2024/7/17.
+//
+
+#ifndef PROJECT_MARCO_H
+#define PROJECT_MARCO_H
+
+#include "studio_macros.h"
+
+#include "log/studio_log.h"
+
+#include "singleton/studio_singleton.h"
+
+#include "json/studio_json.h"
+
+#endif //PROJECT_MARCO_H

+ 36 - 0
sr71_drive/core/radar_obj.h

@@ -0,0 +1,36 @@
+/**
+  ******************************************************************************
+  * @file           : radar_obj.h
+  * @author         : wangyingjie
+  * @brief          : None
+  * @attention      : None
+  * @date           : 2025/6/20
+  ******************************************************************************
+  */
+
+#ifndef RADAR_OBJ_H
+#define RADAR_OBJ_H
+
+#include "project_marco.h"
+
+struct RadarData
+{
+  unsigned id;
+  unsigned timestamp;
+  std::vector<unsigned char> data;
+};
+
+// 数据接收器接口
+class IDataReceiver
+{
+public:
+  virtual ~IDataReceiver() = default;
+  virtual bool Initialize() = 0;
+  virtual void Start() = 0;
+  virtual void Stop() = 0;
+  virtual void SetDataCallback(std::function<void(const RadarData &)> callback) = 0;
+};
+
+
+
+#endif //RADAR_OBJ_H

+ 149 - 0
sr71_drive/core/rs71_usb_receiver.cpp

@@ -0,0 +1,149 @@
+/**
+  ******************************************************************************
+  * @file           : rs71_usb_receiver.cpp
+  * @author         : wangyingjie
+  * @brief          : None
+  * @attention      : None
+  * @date           : 2025/6/20
+  ******************************************************************************
+  */
+
+#include "rs71_usb_receiver.h"
+
+#include <cstdio>
+#include <cstring>
+
+RS71UsbReceiver::RS71UsbReceiver(unsigned devType, unsigned devIdx, unsigned chMask, unsigned baud)
+    : devType(devType), devIdx(devIdx), chMask(chMask), baud(baud)
+{
+    memset(rxThreads, 0, sizeof(rxThreads));
+}
+
+RS71UsbReceiver::~RS71UsbReceiver()
+{
+    Stop();
+    Close();
+}
+
+bool RS71UsbReceiver::init(unsigned devType, unsigned devIdx, unsigned chMask, unsigned baud)
+{
+    this->devType = devType;
+    this->devIdx = devIdx;
+    this->chMask = chMask;
+    this->baud = baud;
+    memset(rxThreads, 0, sizeof(rxThreads));
+    return true;
+}
+
+bool RS71UsbReceiver::Open()
+{
+    if (!VCI_OpenDevice(devType, devIdx, 0))
+    {
+        printf("VCI_OpenDevice failed\n");
+        return false;
+    }
+    printf("VCI_OpenDevice succeeded\n");
+    return true;
+}
+
+void RS71UsbReceiver::Close()
+{
+    VCI_CloseDevice(devType, devIdx);
+    printf("VCI_CloseDevice\n");
+}
+
+bool RS71UsbReceiver::Start()
+{
+    VCI_INIT_CONFIG config = {
+        0,
+        0xFFFFFFFF,
+        1,
+        0,
+        static_cast<UCHAR>(baud & 0xff),
+        static_cast<UCHAR>(baud >> 8)
+    };
+
+    for (int i = 0; i < 4; i++)
+    {
+        if ((chMask & (1 << i)) == 0)
+            continue;
+
+        if (!VCI_InitCAN(devType, devIdx, i, &config))
+        {
+            printf("VCI_InitCAN(%d) failed\n", i);
+            return false;
+        }
+        if (!VCI_StartCAN(devType, devIdx, i))
+        {
+            printf("VCI_StartCAN(%d) failed\n", i);
+            return false;
+        }
+
+        // 启动接收线程
+        rxContexts[i].channel = i;
+        rxContexts[i].stop = false;
+#ifdef WIN32
+        rxThreads[i] = (HANDLE)_beginthreadex(NULL, 0, RxThreadFunc, &rxContexts[i], 0, NULL);
+#else
+        pthread_create(&rxThreads[i], nullptr, RxThreadFunc, &rxContexts[i]);
+#endif
+    }
+
+    return true;
+}
+
+void RS71UsbReceiver::Stop()
+{
+    for (int i = 0; i < 4; i++)
+    {
+        if ((chMask & (1 << i)) == 0)
+            continue;
+        rxContexts[i].stop = true;
+#ifdef WIN32
+        WaitForSingleObject(rxThreads[i], INFINITE);
+        CloseHandle(rxThreads[i]);
+#else
+        pthread_join(rxThreads[i], nullptr);
+#endif
+    }
+}
+
+std::vector<RS71UsbReceiver::CanFrame> RS71UsbReceiver::GetReceivedData(unsigned channel)
+{
+    if (channel >= 4)
+    {
+        return {};
+    }
+    std::lock_guard<std::mutex> lock(rxContexts[channel].mtx);
+    return rxContexts[channel].buffer;
+}
+
+THREAD_RETURN RS71UsbReceiver::RxThreadFunc(void *param)
+{
+    RX_CTX *ctx = static_cast<RX_CTX *>(param);
+    VCI_CAN_OBJ can[RX_BUFF_SIZE];
+
+    while (!ctx->stop)
+    {
+        int cnt = VCI_Receive(3, 0, ctx->channel, can, RX_BUFF_SIZE, RX_WAIT_TIME);
+        if (cnt <= 0)
+            continue;
+
+        std::lock_guard<std::mutex> lock(ctx->mtx);
+        for (int i = 0; i < cnt; ++i)
+        {
+            CanFrame frame;
+            frame.id = can[i].ID;
+            frame.timestamp = can[i].TimeStamp;
+            frame.data.assign(can[i].Data, can[i].Data + can[i].DataLen);
+            ctx->buffer.push_back(frame);
+        }
+    }
+
+#ifdef WIN32
+    _endthreadex(0);
+    return 0;
+#else
+    pthread_exit(0);
+#endif
+}

+ 87 - 0
sr71_drive/core/rs71_usb_receiver.h

@@ -0,0 +1,87 @@
+/**
+  ******************************************************************************
+  * @file           : rs71_usb_receiver.h
+  * @author         : wangyingjie
+  * @brief          : None
+  * @attention      : None
+  * @date           : 2025/6/20
+  ******************************************************************************
+  */
+
+#ifndef RS71_USB_RECEIVER_H
+#define RS71_USB_RECEIVER_H
+
+#ifndef CAN_DEVICE_H
+#define CAN_DEVICE_H
+
+#include <vector>
+#include <string>
+#include <mutex>
+
+#ifdef WIN32
+#include <windows.h>
+#include <process.h>
+typedef HANDLE ThreadHandle;
+#define THREAD_RETURN unsigned __stdcall
+#else
+#include <pthread.h>
+#include <unistd.h>
+#define THREAD_RETURN void*
+typedef pthread_t ThreadHandle;
+#endif
+
+#include "controlcan.h"
+
+#define RX_BUFF_SIZE 1000
+#define RX_WAIT_TIME 100
+
+class RS71UsbReceiver
+{
+public:
+    RS71UsbReceiver(unsigned devType, unsigned devIdx, unsigned chMask, unsigned baud);
+
+    ~RS71UsbReceiver();
+
+    bool init(unsigned devType, unsigned devIdx, unsigned chMask, unsigned baud);
+
+    bool Open();
+
+    void Close();
+
+    bool Start();
+
+    void Stop();
+
+    struct CanFrame
+    {
+        unsigned int id;
+        unsigned int timestamp;
+        std::vector<unsigned char> data;
+    };
+
+    std::vector<CanFrame> GetReceivedData(unsigned channel);
+
+private:
+    struct RX_CTX
+    {
+        unsigned channel;
+        volatile bool stop;
+        std::vector<CanFrame> buffer;
+        std::mutex mtx;
+    };
+
+    static THREAD_RETURN RxThreadFunc(void *param);
+
+    unsigned devType, devIdx, chMask, baud;
+    RX_CTX rxContexts[4];
+    ThreadHandle rxThreads[4];
+
+#ifdef WIN32
+  static unsigned __stdcall RxThreadWrapper(void* param);
+#endif
+};
+
+#endif
+
+
+#endif //RS71_USB_RECEIVER_H

+ 16 - 0
sr71_drive/src/CMakeLists.txt

@@ -0,0 +1,16 @@
+cmake_minimum_required (VERSION 3.15)
+
+project(RS71_test CXX)
+
+add_executable(${PROJECT_NAME}  "main.cpp" )
+target_link_libraries(${PROJECT_NAME} PUBLIC core_lib)
+
+
+add_executable(test_1  "test_1.cpp" )
+target_link_libraries(test_1 PUBLIC core_lib)
+target_link_libraries(test_1 PUBLIC usbcan)
+
+
+
+
+

+ 107 - 0
sr71_drive/src/main.cpp

@@ -0,0 +1,107 @@
+#include "project_marco.h"
+#include "rs71_usb_receiver.h"
+
+struct TargetListHeader
+{
+    uint8_t object_num; // 目标数量
+    uint16_t measurement_count; // 循环计数
+    uint8_t interface_version; // CAN接口版本号,默认为0
+};
+
+struct TargetInfo
+{
+    uint8_t id; // 目标ID
+    float distance_long; // 目标纵向距离 (m)
+    float distance_lat; // 目标横向距离 (m)
+    float velocity_long; // 目标纵向速度 (m/s)
+    uint8_t dyn_prop; // 动态属性
+    float velocity_lat; // 目标横向速度 (m/s)
+    float rcs; // RCS
+};
+
+int main()
+{
+    RS71UsbReceiver dev(3, 0, 0x1, 0x1c00); // 参数依次为 DevType, DevIdx, ChMask, Baud
+
+    if (!dev.Open())
+        return -1;
+
+    if (!dev.Start())
+        return -1;
+
+    while (true)
+    {
+        std::vector<RS71UsbReceiver::CanFrame> data = dev.GetReceivedData(0); // 获取第0路CAN数据
+        printf("Frame Count: %zu\n", data.size());
+        for (const auto &frame: data)
+        {
+            // 测试打印查看 -------
+            printf("ID: 0x%X TimeStamp: %u Data:", frame.id, frame.timestamp);
+            for (auto byte: frame.data)
+            {
+                printf(" %02X", byte);
+            }
+            printf("\n");
+            // 测试打印查看 -------
+
+            // 解析数据
+            if (frame.id == 0x60B && frame.data.size() >= 8)
+            {
+                TargetInfo target;
+                // 目标ID (字节0)
+                target.id = frame.data[0];
+                // 目标纵向距离
+                target.distance_long = (frame.data[1] * 32 + (frame.data[2] >> 3)) * 0.1 - 500;
+                // 目标横向距离
+                target.distance_lat = ((frame.data[2] & 0x07) * 256 + frame.data[3]) * 0.1 - 102.3;
+                // 目标纵向速度
+                target.velocity_long = (frame.data[4] * 4 + (frame.data[5] >> 6)) * 0.25 - 128;
+                // 目标横向速度
+                target.velocity_lat = ((frame.data[5] & 0x3F) * 8 + (frame.data[6] >> 5)) * 0.25 - 64;
+                // 动态属性
+                target.dyn_prop = (frame.data[6] & 0x07);
+                // RCS
+                target.rcs = (frame.data[7] * 0.5) - 64;
+                // 打印结果
+                printf("Target ID: %u\n", target.id);
+                printf("Distance Longitudinal: %.2fm\n", target.distance_long);
+                printf("Distance Lateral: %.2fm\n", target.distance_lat);
+                printf("Velocity Longitudinal: %.2fm/s\n", target.velocity_long);
+                printf("Dynamic Property: %u\n", target.dyn_prop);
+                printf("Velocity Lateral: %.2fm/s\n", target.velocity_lat);
+                printf("RCS: %.2fdB㎡\n", target.rcs);
+
+                // 计算目标径向距离和角度
+                float radial_distance = sqrt(
+                    target.distance_long * target.distance_long + target.distance_lat * target.distance_lat);
+                float theta = atan2(target.distance_lat, target.distance_long) * 180 / M_PI; // 转换为度数
+                printf("Radial Distance: %.2fm\n", radial_distance);
+                printf("Angle (θ): %.2f°\n", theta);
+
+                // 计算目标速度
+                float velocity = target.velocity_long * cos(theta * M_PI / 180) + target.velocity_lat * sin(
+                                     theta * M_PI / 180);
+                printf("Velocity: %.2fm/s\n", velocity);
+            } else if (frame.id == 0x60A)
+            {
+                std::cout << "-------------" << std::endl;
+                TargetListHeader header;
+
+                // 解析目标数量
+                header.object_num = frame.data[0];
+                printf("Object Number: %d\n", header.object_num);
+                // 解析循环计数
+                header.measurement_count = (static_cast<uint16_t>(frame.data[3]) << 8) | frame.data[2];
+                printf("Measurement Count: %d\n", header.measurement_count);
+                // // 解析CAN接口版本号
+                // header.interface_version = (frame.data[4] >> 4) & 0x0F;
+                // printf("Interface Version: %d\n", header.interface_version);
+            }
+        }
+        std::this_thread::sleep_for(std::chrono::microseconds(20));
+    }
+
+    dev.Stop();
+    dev.Close();
+    return 0;
+}

+ 235 - 0
sr71_drive/src/test_1.cpp

@@ -0,0 +1,235 @@
+/**
+  ******************************************************************************
+  * @file           : test_1.cpp
+  * @author         : wangyingjie
+  * @brief          : None
+  * @attention      : None
+  * @date           : 2025/6/20
+  ******************************************************************************
+  */
+
+
+#ifdef WIN32 // for windows
+#include <windows.h>
+#include <process.h>
+#include <stdio.h>
+#include <time.h>
+#include "controlcan.h"
+#pragma comment(lib, "controlcan.lib")
+#define msleep(ms) Sleep(ms)
+typedef HANDLE pthread_t;
+#else // for linux
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <strings.h>
+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <pthread.h>
+#include "controlcan.h"
+#define msleep(ms) usleep((ms) * 1000)
+#define min(a, b) (((a) < (b)) ? (a) : (b))
+#endif
+
+#define MAX_CHANNELS 4
+#define CHECK_POINT 200
+#define RX_WAIT_TIME 100
+#define RX_BUFF_SIZE 1000
+
+unsigned gDevType = 0;  // 设备类型号
+unsigned gDevIdx = 0;   // 设备索引,第一个设备是0,第二个相同信号设备是1
+unsigned gChMask = 0;   // 通道掩码,CAN0 = 1,CAN1=2,CAN0+CAN1=3
+unsigned gBaud = 0;     // 波特率
+unsigned gTxType = 0;   // 发送类型,正常发送=0,单次发送=1,自发自收=2,单次自发自收=3
+unsigned gTxSleep = 0;  // 发送帧间隔
+unsigned gTxFrames = 0; // 每次发送帧数
+unsigned gTxCount = 0;  // 发送次数
+
+// 将字符串表示的十六进制数转换为无符号整数
+unsigned s2n(const char *s)
+{
+    unsigned l = strlen(s);
+    unsigned v = 0;
+    unsigned h = (l > 2 && s[0] == '0' && (s[1] == 'x' || s[1] == 'X'));
+    unsigned char c;
+    unsigned char t;
+    if (!h)
+        return atoi(s);
+    if (l > 10)
+        return 0;
+    for (s += 2; c = *s; s++)
+    {
+        if (c >= 'A' && c <= 'F')
+            c += 32;
+        if (c >= '0' && c <= '9')
+            t = c - '0';
+        else if (c >= 'a' && c <= 'f')
+            t = c - 'a' + 10;
+        else
+            return 0;
+        v = (v << 4) | t;
+    }
+    return v;
+}
+
+typedef struct
+{
+    unsigned channel; // channel index, 0~3   通道索引
+    unsigned stop;    // stop RX-thread   停止接受线程标志
+    unsigned total;   // total received   接收到的总数据量
+    unsigned error;   // error(s) detected   错误数量
+} RX_CTX;
+
+#ifdef WIN32
+unsigned __stdcall rx_thread(void *data)
+#else
+void *rx_thread(void *data)
+#endif
+{
+    RX_CTX *ctx = (RX_CTX *)data;
+    ctx->total = 0; // reset counter  重置计数器
+
+    VCI_CAN_OBJ can[RX_BUFF_SIZE]; // buffer
+    int cnt;                       // current received
+    int i;
+
+    unsigned check_point = 0;
+    while (!ctx->stop) // 在不停止的情况下
+    {
+        cnt = VCI_Receive(gDevType, gDevIdx, ctx->channel, can, RX_BUFF_SIZE, RX_WAIT_TIME); // 接受函数,返回读取到的帧数
+        if (!cnt)
+            continue;
+        for (i = 0; i < cnt; i++)
+        {
+            printf("ID: 0X%X  ", can[i].ID);
+            printf("TimeStamp: %d  ", can[i].TimeStamp);
+            printf("Data: ");
+            for (int j = 0; j < can[i].DataLen; j++)
+            {
+                printf("%02X ", can[i].Data[j]);
+            }
+            printf("\n");
+        }
+    }
+    printf("CAN%d RX thread terminated\n", ctx->channel);
+
+#ifdef WIN32
+    _endthreadex(0);
+    return 0;
+#else
+    pthread_exit(0);
+#endif
+}
+
+int test()
+{
+    // ----- init & start -------------------------------------------------
+
+    // 板卡初始化结构体
+    VCI_INIT_CONFIG config;
+    config.AccCode = 0;            //  验收码
+    config.AccMask = 0xffffffff;   // 屏蔽码
+    config.Filter = 1;             // 滤波方式,1表示单滤波,0表示双滤波
+    config.Mode = 0;               // 0表示正常模式,1表示只听模式
+    config.Timing0 = gBaud & 0xff; // 波特率定时器0
+    config.Timing1 = gBaud >> 8;   // 波特率定时器1
+
+    int i, j;
+    for (i = 0; i < MAX_CHANNELS; i++)
+    {
+        if ((gChMask & (1 << i)) == 0)
+            continue;
+
+        // 初始化CAN通道   设备类型号,设备索引号,第几路CAN,初始化参数结构(VCI_INIT_CONFIG结构体变量)
+        if (!VCI_InitCAN(gDevType, gDevIdx, i, &config))
+        {
+            printf("VCI_InitCAN(%d) failed\n", i);
+            return 0;
+        }
+        printf("VCI_InitCAN(%d) succeeded\n", i);
+
+        // 启动CAN通道   设备类型号,设备索引号,第几路CAN
+        if (!VCI_StartCAN(gDevType, gDevIdx, i))
+        {
+            printf("VCI_StartCAN(%d) failed\n", i);
+            return 0;
+        }
+        printf("VCI_StartCAN(%d) succeeded\n", i);
+    }
+
+    VCI_CAN_OBJ can;
+
+    // 创建接收线程
+    RX_CTX rx_ctx[MAX_CHANNELS];
+    pthread_t rx_threads[MAX_CHANNELS];
+    for (i = 0; i < MAX_CHANNELS; i++)
+    {
+        if ((gChMask & (1 << i)) == 0)
+            continue;
+
+        rx_ctx[i].channel = i;
+        rx_ctx[i].stop = 0;
+        rx_ctx[i].total = 0;
+        rx_ctx[i].error = 0;
+#ifdef WIN32
+        rx_threads[i] = (HANDLE)_beginthreadex(NULL, 0, rx_thread, &rx_ctx[i], 0, NULL);
+#else
+        pthread_create(&rx_threads[i], NULL, rx_thread, &rx_ctx[i]); // 创建一个新的线程
+#endif
+    }
+
+    // 停止接收
+    printf("<ENTER> to terminate RX-threads...\n");
+    getchar();
+    for (i = 0; i < MAX_CHANNELS; i++)
+    {
+        if ((gChMask & (1 << i)) == 0)
+            continue;
+        rx_ctx[i].stop = 1;
+    }
+}
+
+int main(int argc, char *argv[])
+{
+    // if (argc < 5)
+    // {
+    //     printf("test [DevType] [DevIdx] [ChMask] [Baud]\n"
+    //            "    example: test 3 0 1 0x1c00 \n"
+    //            "                  | | | |\n"
+    //            "                  | | | |0x1400-1M, 0x1c00-500K, 0x1C01-250K ....\n"
+    //            "                  | | |\n"
+    //            "                  | | |bit0-CAN1, bit1-CAN2, bit2-CAN3, bit3-CAN4, 3=CAN1+CAN2, 7=CAN1+CAN2+CAN3\n"
+    //            "                  | |\n"
+    //            "                  | |Card0\n"
+    //            "                  |\n"
+    //            "                  |3-usbcan-i, 4-usbcan-ii ....\n");
+    //     return 0;
+    // }
+    // gDevType = s2n(argv[1]);
+    // gDevIdx = s2n(argv[2]);
+    // gChMask = s2n(argv[3]);
+    // gBaud = s2n(argv[4]);
+
+    gDevType = s2n("3");
+    gDevIdx = s2n("0");
+    gChMask = s2n("1");
+    gBaud = s2n("0x1c00");
+    printf("DevType=%d, DevIdx=%d, ChMask=0x%x, Baud=0x%04x\n", gDevType, gDevIdx, gChMask, gBaud);
+
+    // 打开设备  设备类型号,设备索引号,0
+    if (!VCI_OpenDevice(gDevType, gDevIdx, 0))
+    {
+        printf("VCI_OpenDevice failed\n");
+        return 0;
+    }
+    printf("VCI_OpenDevice succeeded\n");
+
+    test();
+
+    // 关闭设备  设备类型号,设备索引号
+    VCI_CloseDevice(gDevType, gDevIdx);
+    printf("VCI_CloseDevice\n");
+    return 0;
+}