前言 在上一篇博客中mmWave_Tutorial1 我们讲述了关于Ti官方demo数据读取以及数据使用并给出了一段实例程序, 细心的读者在使用完历程后会发现ti官方demo所输出的点云数据非常的稀疏, 这一部分是由于mmwave设备天线的稀疏, 一部分是由于在ti官方demo中, 角度估计使用的是传统波束形成的方法其在天线维进行fft来进行角度估计, 而这样稀疏的点云数据不利于我们进行后续更高阶的应用, 而在TI IndustrialToolbox 的 3D people counting demo 中使用了 Capon自适应波束形成算法, 能够生成相对密集的点云, 为我们后续进行聚类, 目标跟踪行为识别等算法的实现提供了基础. 程序的源码, 预编译二进制文件以及相应的说明文档可以在如下的目录中找到.
\ti\mmwave_industrial_toolbox_4_5_1\labs\people_counting\68xx_3D_people_counting
需要注意的是在这篇博客当中所使用到的硬件设备为IWR6843ISK,IWR8843ISK-AOP或者IWR6843ISK-ODS. 同样IWR1843Boost也可以使用
在这篇博客中我们利用之前的方法来对TI IndustrialToolbox 中的 3D people counting demo 进行上位机程序的编写, 来实现数据的解析与读取.
3D people counting demo概述 与ti out of box demo相比 3D people counting demo实现了如下两个新的功能:
雷达前端信号处理链( 包含Capon自适应波数形成算法)
gtrack多目标跟踪算法
3D people counting demo的框图如下图所示 需要注意的是gtrack多目标跟踪算法是实现在ARM上的
同时由于xWRxx43的雷达SoC采用了3发4收的天线通道, 与iwr1642相比, 收获了在俯仰角(elevation)上的分辨能力而不单单仅限于方位角(azimuth)上的分辨能力, 而不同的天线布局会影响到后级的信号处理, 在本篇博客中我不会去详细的介绍信号处理我将会将重点放在如何读取从雷达返回的已经处理好的点云数据.
数据传输以及格式 CLI port 数据传输及格式 在之前讲述ti out of box demo 我们提到了 CLI port 是用来发送对demo程序的配置信息, 而在 3D people counting demo中, 不同于 ti out of box demo的任务, 3D people counting demo需要进行天线阵列排布, 房间边界, 状态参数等等的配置, 所以它的 CLI port数据传输的格式与相应的意义与ti out of box demo 就有所不同
具体的数据传输格式以及相应的含义可以在如下文档中的Modifying Configuration File的章节中找到
/ti/mmwave_industrial_toolbox_4_5_1/labs/people_counting/68xx_3D_people_counting/docs/3d_pplcount_user_guide.pdf
Data port 数据传输及格式 与在ti out of box demo相似, 3D people counting 在数据传输时使用了 类似的 TLV 格式, 如下图所示
与ti out of box demo 不同的是,TLV的定义与数据传输的格式, 具体的数据传输格式可以在如下文档中的 Data Formats 的章节中找到
/ti/mmwave_industrial_toolbox_4_5_1/labs/people_counting/68xx_3D_people_counting/docs/3d_pplcount_user_guide.pdf
3D people counting user Guide中我们可以看到 3D people counting 的 TLV 有如下三种,分别是
Point Cloud TLV
Target Object TLV
Target Index TLV
Point Cloud TLV用于传输雷达信号处理得到的点云数据, Target Object TLV用于输出gtrack算法输出的 target 的状态 比如位置, 速度, 加速度等, Target Index TLV 用于输出每个target 的独立的编号. 它的数据定义也是通过结构体来实现的, 我们可以参考ti out of box demo 从有关的定义来进行驱动程序的编写
相关代码(Matlab)
注意 : 为了方便读者的使用, 我已经将3D people counting demo 中进行了修改, 删除了其中目标跟踪的部分并编译成了二进制文件, 需要请联系我
这部分的代码与 ti out of box demo 类似, 但是为了方便读者们复制粘贴使用 使用, 在这里依然给出相应的各个功能部分的代码, Data port 数据传输及格式的不同带来的变化主要反映在函数 function [dataOk, frameNumber, detObj] = readAndParseData(DATA_sphandle) 中
打开传输串口 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 function [CLI_sphandle,DATA_sphandle] = setupUART (CLIcomPortString,DATAcomPortString) if strcmp(CLIcomPortString(1 :3 ),'COM' ) || strcmp(DATAcomPortString(1 :3 ),'COM' ) CLI_sphandle = serial(CLIcomPortString,'BaudRate' ,115200 ); set(CLI_sphandle,'Parity' ,'none' ) set(CLI_sphandle,'Terminator' ,'LF' ) fopen(CLI_sphandle); DATA_sphandle = serial(DATAcomPortString,'BaudRate' ,921600 ); set(DATA_sphandle,'Terminator' , '' ); set(DATA_sphandle,'InputBufferSize' , 65536 ); set(DATA_sphandle,'Timeout' ,10 ); set(DATA_sphandle,'ErrorFcn' ,@dispError); set(DATA_sphandle,'BytesAvailableFcnMode' ,'byte' ); set(DATA_sphandle,'BytesAvailableFcnCount' , 2 ^16 +1 ); set(DATA_sphandle,'BytesAvailableFcn' ,@readUartCallbackFcn); fopen(DATA_sphandle); else fprintf('COM port string format wrong\n' ); end end
CLI port配置数据 这个 CLI port 的配置数据是用来配置IWR8843ISK-AOP, 其他的型号的mmWave雷达开发板的有关配置可以在如下的文件中找到
\ti\mmwave_industrial_toolbox_4_5_1\labs\people_counting\68xx_3D_people_counting\chirp_configs
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 sensorStop flushCfg dfeDataOutputMode 1 channelCfg 15 7 0 adcCfg 2 1 adcbufCfg -1 0 1 1 1 lowPower 0 0 profileCfg 0 60.75 7 7 41.10 0 0 54.71 1 96 2950.00 0 0 36 chirpCfg 0 0 0 0 0 0 0 1 chirpCfg 1 1 0 0 0 0 0 2 chirpCfg 2 2 0 0 0 0 0 4 frameCfg 0 2 96 0 50 1 0 dynamicRACfarCfg -1 4 4 2 4 8 16 4 4 4.00 4.50 0.50 1 1 staticRACfarCfg -1 4 4 2 4 8 16 4 6 12.00 13.00 0.30 0 0 dynamicRangeAngleCfg -1 0.75 0.0010 1 0 dynamic2DAngleCfg -1 1.5 0.0300 1 0 1 0.50 0.85 8.00 staticRangeAngleCfg -1 1 8 4 antGeometry0 -1 -1 0 0 -3 -3 -2 -2 -1 -1 0 0 antGeometry1 -1 0 -1 0 -3 -2 -3 -2 -3 -2 -3 -2 antPhaseRot 1 -1 1 -1 1 -1 1 -1 1 -1 1 -1 fovCfg -1 70.0 20.0 compRangeBiasAndRxChanPhase 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 staticBoundaryBox -2 2 2 8.5 -2 2 boundaryBox -2.5 2.5 0.5 9 -2.5 2.5 sensorPosition 2 0 0 gatingParam 3 2 2 2 0 stateParam 3 3 10 40 5 600 allocationParam 00 800 0.1 15 0.1 20 trackingCfg 1 2 1000 20 67 105 50 sensorStart
读取CLI port配置数据 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 function [configcmd] = readCfgFile (configFile) configcmd = cell(1 ,100 ); fid = fopen(configFile, 'r' ); if fid == -1 fprintf('File %s not found!\n' , configFile); return ; else fprintf('Opening configuration file %s ...\n' , configFile); end tline = fgetl(fid); k=1 ; while ischar(tline) if ~isempty (tline) configcmd{k} = tline; k = k + 1 ; end tline = fgetl(fid); end configcmd = configcmd(1 :k-1 ); fclose(fid); end
发送CLI port的配置数据 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 function sendCfg (UART_sphandle,configcmd) mmwDemoCliPrompt = char('mmwDemo:/>' ); fprintf('Sending configuration to IWR radar\n' ); for k=1 :length (configcmd) command = configcmd{k}; fprintf(UART_sphandle, command); fprintf('%s\n' , command); echo = fgetl(UART_sphandle); done = fgetl(UART_sphandle); fprintf('%s\n' , done); prompt = fread(UART_sphandle, size (mmwDemoCliPrompt,2 )); fprintf('%s\n' , prompt); end end
读取Data port数据 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 function [dataOk, frameNumber, pointStruct,targetStruct2D] = readAndParseData (DATA_sphandle) pointStruct_SIZE_BYTES = 8 ; targetStruct2D_SIZE_BYTES = 40 ; BYTE_VEC_ACC_MAX_SIZE = 2 ^16 ; POINT_CLOUD_2D = 6 ; TARGET_LIST_3D = 7 ; TARGET_INDEX = 8 ; maxBufferSize = BYTE_VEC_ACC_MAX_SIZE; pointStruct =[]; targetStruct2D = []; frameNumber = 0 ; persistent byteBuffer if isempty (byteBuffer) byteBuffer = zeros (maxBufferSize,1 ); end persistent byteBufferLength if isempty (byteBufferLength) byteBufferLength = 0 ; end persistent magiNotOkCounter if isempty (magiNotOkCounter) magiNotOkCounter = 0 ; end magicOk = 0 ; dataOk = 0 ; bytesToRead = get(DATA_sphandle,'BytesAvailable' ); if (bytesToRead ~= 0 ) [bytevec, byteCount] = fread(DATA_sphandle, bytesToRead, 'uint8' ); if (byteBufferLength + byteCount < maxBufferSize) byteBuffer(byteBufferLength+1 :byteBufferLength + byteCount) = bytevec(1 :byteCount); byteBufferLength = byteBufferLength + byteCount; end end if byteBufferLength > 16 byteBufferStr = char(byteBuffer); startIdx = strfind(byteBufferStr', char([2 1 4 3 6 5 8 7 ])); if ~isempty (startIdx) if length (startIdx) >= 2 if startIdx(end -1 ) > 1 byteBuffer(1 :byteBufferLength-(startIdx(1 )-1 )) = byteBuffer(startIdx(1 ):byteBufferLength); byteBufferLength = byteBufferLength - (startIdx(1 )-1 ); end else if startIdx(1 ) > 1 byteBuffer(1 :byteBufferLength-(startIdx(1 )-1 )) = byteBuffer(startIdx(1 ):byteBufferLength); byteBufferLength = byteBufferLength - (startIdx(1 )-1 ); end end if byteBufferLength < 0 byteBufferLength = 0 ; end totalPacketLen = sum(byteBuffer(8 +4 +[1 :4 ]) .* [1 256 65536 16777216 ]'); if ((byteBufferLength >= totalPacketLen) && (byteBufferLength ~= 0 )) magicOk = 1 ; else magicOk = 0 ; end end end if (magicOk == 1 ) word = [1 256 65536 16777216 ]'; idx = 0 ; magicNumber = byteBuffer(idx + 1 :8 ); idx = idx + 8 ; Header.version = dec2hex(sum(byteBuffer(idx+[1 :4 ]) .* word)); idx = idx + 4 ; Header.totalPacketLen = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.platform = dec2hex(sum(byteBuffer(idx+[1 :4 ]) .* word)); idx = idx + 4 ; Header.frameNumber = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); frameNumber = Header.frameNumber; idx = idx + 4 ; Header.subFrameNumber = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.chirpProcessingMargin = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.frameProcessingMargin = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.trackProcessTime = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.uartSentTime = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; Header.numTLVs = typecast(uint8(byteBuffer(idx+(1 :2 ))),'uint16' ); idx = idx + 2 ; Header.checksum = typecast(uint8(byteBuffer(idx+(1 :2 ))),'uint16' ); idx = idx + 2 ; for tlvIdx = 1 :Header.numTLVs tlv.type = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; tlv.length = typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' ); idx = idx + 4 ; switch tlv.type case POINT_CLOUD_2D numberOfPoints = (tlv.length - 28 )/pointStruct_SIZE_BYTES; pointUnit.elevationUnit = typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' ); idx = idx + 4 ; pointUnit.azimuthUnit = typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' ); idx = idx + 4 ; pointUnit.dopplerUnit = typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' ); idx = idx + 4 ; pointUnit.rangeUnit = typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' ); idx = idx + 4 ; pointUnit.snrUnit = typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' ); idx = idx + 4 ; pointStruct.elevation =[]; pointStruct.azimuth =[]; pointStruct.doppler =[]; pointStruct.range =[]; pointStruct.snr =[]; if numberOfPoints > 0 for i = 1 :numberOfPoints pointStruct.elevation = [pointStruct.elevation single(typecast(uint8(byteBuffer(idx+1 )),'int8' ))*pointUnit.elevationUnit]; idx = idx + 1 ; pointStruct.azimuth = [pointStruct.azimuth single(typecast(uint8(byteBuffer(idx+1 )),'int8' ))*pointUnit.azimuthUnit]; idx = idx + 1 ; pointStruct.doppler = [pointStruct.doppler single(typecast(uint8(byteBuffer(idx+(1 :2 ))),'int16' ))*pointUnit.dopplerUnit]; idx = idx + 2 ; pointStruct.range = [pointStruct.range single(typecast(uint8(byteBuffer(idx+(1 :2 ))),'uint16' ))*pointUnit.rangeUnit]; idx = idx + 2 ; pointStruct.snr = [pointStruct.snr single(typecast(uint8(byteBuffer(idx+(1 :2 ))),'uint16' ))*pointUnit.snrUnit]; idx = idx + 2 ; end dataOk = 1 ; end case TARGET_LIST_3D numberOfTargets = (tlv.length - 28 )/targetStruct2D_SIZE_BYTES; if tlv.length > 0 targetStruct2D.tid = []; targetStruct2D.posX = []; targetStruct2D.posY = []; targetStruct2D.velX = []; targetStruct2D.velY = []; targetStruct2D.accX = []; targetStruct2D.accY = []; targetStruct2D.posZ = []; targetStruct2D.velZ = []; targetStruct2D.accZ = []; if numberOfPoints > 0 for i = 1 :numberOfPoints targetStruct2D.tid = [targetStruct2D.tid typecast(uint8(byteBuffer(idx+(1 :4 ))),'uint32' )]; idx = idx + 4 ; targetStruct2D.posX = [targetStruct2D.posX typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.posY = [targetStruct2D.posY typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.velX = [targetStruct2D.velX typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.velY = [targetStruct2D.velY typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.accX = [targetStruct2D.accX typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.accY = [targetStruct2D.accY typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.posZ = [targetStruct2D.posZ typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.velZ = [targetStruct2D.velZ typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; targetStruct2D.accZ = [targetStruct2D.accZ typecast(uint8(byteBuffer(idx+(1 :4 ))),'single' )]; idx = idx + 4 ; end end dataOk = 1 ; end case TARGET_INDEX end end if idx > 0 shiftSize = Header.totalPacketLen; byteBuffer(1 : byteBufferLength-shiftSize) = byteBuffer(shiftSize+1 :byteBufferLength); byteBufferLength = byteBufferLength - shiftSize; if byteBufferLength < 0 byteBufferLength = 0 ; end end else magiNotOkCounter = magiNotOkCounter + 1 ; end
示例程序 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 clear all close all clc VisualReview = 1 ; FallDetection = 0 ; delete(instrfind); configFile = "AOPconfig.cfg" ; configcmd = readCfgFile(configFile); [CLI_sphandle,DATA_sphandle] = setupUART('COM3' ,'COM5' ); sendCfg(CLI_sphandle,configcmd); limit = 4 ; N= 10000 ; figure H1 = uicontrol('Style' , 'PushButton' , ... 'String' , 'Shutdown' , ... 'Callback' , 'shutVal = 1' ,'InnerPosition' ,[7 ,30 ,60 ,20 ]); H2 = uicontrol('Style' , 'PushButton' , ... 'String' , 'Stop' , ... 'Callback' , 'stopVal = 1' ,'InnerPosition' ,[7 ,60 ,60 ,20 ]); H3 = uicontrol('Style' , 'PushButton' , ... 'String' , 'Start' , ... 'Callback' , 'startVal = 1' ,'InnerPosition' ,[7 ,90 ,60 ,20 ]); h0 = scatter3 ([],[],[],'filled' ); axis([-limit,limit,0 ,7 ,-1.5 ,1.5 ]); xlabel('X (m)' ); ylabel('Y (m)' );zlabel('Z (m)' ); myInd = 1 ; dataOk = 0 ; stopVal = 0 ; startVal = 0 ; shutVal = 0 ; mask = 0 ; frame = []; while (myInd <= N) dataOk = 0 ; if mask ==1 pause(0.1 ); else [dataOk, frameNumber, pointStruct,targetStruct2D] = readAndParseData(DATA_sphandle); end if stopVal == 1 stopVal = 0 ; mask = 1 ; fprintf(CLI_sphandle, 'sensorStop\n' ); end if startVal == 1 startVal = 0 ; mask = 0 ; fprintf(CLI_sphandle, 'sensorStart 0\n' ); end if shutVal == 1 shutVal = 0 ; fprintf(CLI_sphandle, 'sensorStop\n' ); break ; end if dataOk == 1 XData = []; YData = []; ZData = []; graphXData = []; graphYData = []; graphZData = []; processingSignal = [pointStruct.elevation ;pointStruct.azimuth;pointStruct.doppler;pointStruct.range;pointStruct.snr]; frame{myInd} = processingSignal'; if VisualReview if myInd>3 showData = [frame{myInd}; frame{myInd-1 }; frame{myInd-2 }]; else showData = frame{myInd}; end temp = showData(:,4 ) .* cos (showData(:,1 )); pos.XData = temp.*sin (showData(:,2 )); pos.YData = temp.*cos (showData(:,2 )); pos.ZData = showData(:,4 ) .* sin (showData(:,1 )); pos.Doppler = showData(:,3 ); pos.SNR = showData(:,5 ); h0.XData = pos.XData; h0.YData = pos.YData; h0.ZData = pos.ZData; h0.SizeData = 3 *ones (1 ,length (pos.ZData)); h0.CData = abs (pos.Doppler); title(['Frame No.' num2str(myInd)]); drawnow limitrate; end pause(0.04 ); myInd = myInd + 1 ; end end delete(instrfind); close all