ARS408-21毫米波雷达笔记

参数

在这里插入图片描述

ARS 408 , 德国大陆的毫米波雷达:

  • 型号: ARS408-21(XX, Far Range 250m), ARS408-21SC(特殊的软件版本, 扩展到1200m, 优化目标分类行人检测, 增加多边形配置等), 本篇测的是前者ARS408-21XX

  • 发射频率76…77GHz, 发射功率14.1~35.1dBm, 调制方式FMCW(Frequency Modulated Continuous Wave)

  • 扫描频率17Hz(58.8ms), 但是应用程序的输出周期72ms(70~80ms)

  • 3个测距范围: (Far Range)长距0.2~250m, (Near/Short Range)短距0.2~70m@±45°, 短距0.2~20m@±60°. 前面的0.2m为近距离盲区, 毕竟是波, 近距离来回时间太短的话来不及测量, 包括激光雷达也会有近距离盲区. ARS408的探测区域FoV如图所示: 在这里插入图片描述

  • 天线通道: 4TX/2x6RX = 24 channels = 2TX/6RX far - 2TX/6RX near. 上图也可以看出有4个发射. ARS408 双波束(长距和短距)同时工作,不可切换,检测到的目标按距离远近或者 RCS 大小依次输出,默认按距离由近及远输出

  • 测量分辨率: 1.79m@far range, 0.39m@near range, 满足 1.5 到 2 倍分辨率的条件下可对两个物体进行区分. 精度±0.4m@far, ±0.1m@near

  • 对于常见的目标(乘用车, 摩托车, 自行车, 行人)的范围限制: 在这里插入图片描述
    在这里插入图片描述

  • 速度范围: -400km/h…+200km/h, -指远离leaving object, +指靠近approximation

  • 速度分辨率: 0.37km/h@far, 0.43km/h@near, 精度0.1km/h

  • 供电电压: 8~32V, 典型功耗6.6W, 峰值功耗12W, 实测平均功耗23V*0.26A≈6W

  • 工作温度: 40°C…+85°C

  • 8P接口, 对插的连接器为 1-1534229-1 : AMP 汽车连接器护套 | TE Connectivity 定义为 1-Power, 8-GND, 4-CANL, 7-CANH, 其实办公室内测的话, 直接拿杜邦线插上去就可以, CAN通信速率500Kbit/s

  • 安装方向: 正面的印字要是正的, 或者说出线口离左前轮近(对于不分头尾前后都装毫米波的平板车要注意), 图中Sensor Orientation = 0的方向(图中并不是要前面装2个只是安装方向的示意图) 在这里插入图片描述

  • 安装位置: 车辆水平方向中心±600mm, 垂直方向离地高度295mm~800mm, 不影响性能在这里插入图片描述

  • 输入信号: YawRate(deg/s, 左正右负, 超过172deg/s雷达输出目标数量为0), VehicleSpeed(需要指明静止, 前进还是后退, m/s, 超过115m/s雷达输出目标数量变为0), 可能是为了判断物体是否静止或者多普勒效应的考虑, 周期上建议50ms, Cluster模式不需要输入这两个信号. 一般只需要前向雷达输入, 角雷达不用.

  • 输出信号: 输出模式为(未跟踪)Cluster和(跟踪)Object两种方式, Object模式最多100个目标, Cluster模式最多250个目标. 本篇测试Object方式, 主要是坐标目标的相对速度和角度关系, 其它的还有标准差, 相对加速度, 目标的长宽, 目标的分类(点/汽车/卡车客车/行人/摩托车/自行车/宽大目标)等

连接

基于以下事实:

  • ARS408 CAN通讯速率500Kbit/s, 内部无120Ω终端电阻
  • 8字节标准帧算上填充位, 位数在 111~131位, 平均一下, 按125位计算, 500000/125/1000=4帧/ms=288帧/72ms
  • 如果60B(8字节), 60C(7字节, 简便点按8字节算), 60D(8字节)全部输出的话, 也就最多288/3=96个目标, 如果控制CAN总线负载率60%以下, 最多96*0.6=57.6个目标, 当然一般视野内不会总有这么多目标, 实际负载率会低很多
  • 如果不要60C, 只60B, 60D输出的话, 最多288/2=144个目标, 可以满足文档的最大100个目标
  • 保守点, 一路CAN只挂一个毫米波雷达, 设置输出30~50个目标
  • ARS408-21支持1路CAN上挂载8个毫米波雷达, 需要配置输出ID的不同, 主要是标准帧中间的0~7的改变, 如本来输出60B的, 如果雷达ID配置为7, 那么该帧变为67B, 其它帧的中间那个数字也都会变, 所以一般供应商会给8个DBC文件对应8种不同的雷达ID, 正常只用0即可. 挂这么多当然要精心调教下输出目标数量和输出内容, 确保最坏情况下总线负载不炸
  • 因为500K CAN本身的通信容量限制, 建议一路CAN只挂一个毫米波雷达

下面的测试 把Xavier can1, 毫米波雷达连到一起, 一路CAN只挂一个设备, 接120Ω终端电阻.

配置示例

如雷达配置, 直接发送下面的配置:

# 写入NVM, range排序, 60D输出, 60C输出, objects模式, 标准功率, ID 00, 最大检测距离200m, 继电器不用, 标准灵敏度
can1  200   [8]  FF 19 00 00 08 9D 01 00 

不想计算的话, 也可以写Python脚本, 在Xavier CAN1发出去:

# pip install python-can
# pip install cantools
import can
import cantools
from pprint import pprint

db = cantools.database.load_file('ARS408_id0.dbc')

# for i in range(len(db.messages)):
#     print(db.messages[i])
RadarConfiguration_message = db.get_message_by_name('RadarConfiguration')

# pprint(RadarConfiguration_message.signals)
can_bus = can.interface.Bus(bustype='socketcan', channel='can1', bitrate=500000)
data = RadarConfiguration_message.encode({'RadarCfg_StoreInNVM_valid': 1,\
                                          'RadarCfg_SortIndex_valid': 1,\
                                          'RadarCfg_SendExtInfo_valid': 1,\
                                          'RadarCfg_SendQuality_valid': 1,\
                                          'RadarCfg_OutputType_valid': 1,\
                                          'RadarCfg_RadarPower_valid': 1,\
                                          'RadarCfg_SensorID_valid': 1,\
                                          'RadarCfg_MaxDistance_valid': 1,\
                                          'RadarCfg_MaxDistance': 200,\
                                          'RadarCfg_RadarPower': 0,\
                                          'RadarCfg_OutputType': 1,\
                                          'RadarCfg_SensorID': 0,\
                                          'RadarCfg_StoreInNVM': 1,\
                                          'RadarCfg_SortIndex': 1,\
                                          'RadarCfg_SendExtInfo': 1,\
                                          'RadarCfg_SendQuality': 1,\
                                          'RadarCfg_CtrlRelay': 0,\
                                          'RadarCfg_CtrlRelay_valid': 1,\
                                          'RadarCfg_RCS_Threshold': 0,\
                                          'RadarCfg_RCS_Threshold_Valid': 1})
message = can.Message(arbitration_id=RadarConfiguration_message.frame_id, data=data, is_extended_id=False)
can_bus.send(message)
# can1       200   [8]  FF 19 00 00 08 9D 01 00

其中:

  • 需要先配置好Xavier的can1, 500Kbit/s, 此处略
  • pip安装python-cancantools包, 前者用于CAN收发, 后者用于DBC解析
  • 'RadarCfg_StoreInNVM_valid': 1 中的 1 也可以写成 ‘Valid’ , 写数值和写信号定义是一样的
  • 关闭60C和60D输出可以设置 ‘RadarCfg_SendExtInfo’ 和 ‘RadarCfg_SendQuality’ 的值为0

输出模式: Object(最多100个目标)/Cluster(最多250个目标), 可以在过滤器中配置目标数量, 但有文档不建议用, 因为输出目标不一定在滤波器中, 特别是静止或者被遮挡改变ID的目标.

标定

车辆停在水平方向上, Yaw/Pitch/Roll都需要标定, 可能需要 水平尺, 角度尺, 金属板, 角反射器等, 参见手册, 此处不再赘述.

测试

object目标列表时序图:

在这里插入图片描述

这里用Xavier can1来测试.

先来看正常的输出报文:

$ python3 -m can.viewer -c can1 -i socketcan

Count   Time           dt          ID          DLC  Data
52      51.053085      1.000303    0x201       8    C0 19 00 00 10 F4 00 00
720     51.843109      0.074975    0x60A       4    04 8E 6F 10
3523    51.844130      0.000254    0x60B       8    03 51 A4 11 80 20 41 6C
3523    51.845205      0.000291    0x60C       7    03 7C 61 3A 02 20 E8
3523    51.846200      0.000262    0x60D       8    03 7C EF A6 70 80 19 0B
52      51.053202      1.000233    0x700       4    04 1E 01 00

$ candump -td -x can1
 (000.000000)  can1  RX - -  60A   [4]  02 BA DF 10
 (000.000222)  can1  RX - -  60B   [8]  06 4E 94 00 80 20 01 93
 (000.000257)  can1  RX - -  60B   [8]  01 4F 3C 04 80 20 01 5F
 (000.000278)  can1  RX - -  60C   [7]  06 84 A3 3A 02 20 E8
 (000.000224)  can1  RX - -  60C   [7]  01 7C 61 3A 02 20 E8
 (000.000275)  can1  RX - -  60D   [8]  06 7D 0F A1 70 80 0D 0C
 (000.000251)  can1  RX - -  60D   [8]  01 7D 0F A6 70 80 16 0B
 (000.068508)  can1  RX - -  60A   [4]  02 BA E1 10
 (000.000223)  can1  RX - -  60B   [8]  06 4E 94 00 80 20 01 93
 (000.000286)  can1  RX - -  60B   [8]  01 4F 3C 04 80 20 01 5F
 (000.000296)  can1  RX - -  60C   [7]  06 84 A3 3A 02 20 E8
 (000.000185)  can1  RX - -  60C   [7]  01 7C 61 3A 02 20 E8
 (000.000296)  can1  RX - -  60D   [8]  06 7D 0F A1 70 80 0D 0C
 (000.000235)  can1  RX - -  60D   [8]  01 7D 0F A6 70 80 16 0B
 (000.039077)  can1  RX - -  201   [8]  C0 19 00 00 10 F4 00 00
 (000.000162)  can1  RX - -  700   [4]  04 1E 01 00
 
# can负载率查看
$ canbusload can1@500000
 can1@500000   367   47775  22072   9%

 can1@500000   403   52515  24280  10%

 can1@500000  1222  160350  74512  32%

 can1@500000  1912  251200 116832  50%
 
$ canbusload can1@500000 -r -t -b -c
canbusload 2021-06-11 15:23:40 (worst case bitstuffing)
 can1@500000   100   12620   5696   2% |....................|

其中:

  • 0x201和0x700为状态和版本信息, 1s输出一次
  • 0x60A给出目标数量, 70~80ms输出一次
  • 0x60E为碰撞检测警告, 由于没有使能碰撞检测(0x400), 不输出
  • 60B, 60C, 60D 依次连续输出
  • 这里没有输入yawrate和车速信息
  • can.viewer是按照python-can包自带的
  • candump, canbusload命令找不到的话: sudo apt install can-utils
  • 目标多时总线负载率较高, 60B 60C 60D全部输出时, 大概是1个目标对应1%的负载, 可以通过负载率大致估计输出目标的个数

解析

$ candump can1 | cantools decode --single-line ARS408_id0.dbc
  can1  201   [8]  C0 19 00 00 10 F4 00 00 :: RadarState(RadarState_NVMwriteStatus: 1, RadarState_NVMReadStatus: 'successful', RadarState_MaxDistanceCfg: 200 m, RadarState_Persistent_Error: 'No error', RadarState_Interference: 'No interference', RadarState_Temperature_Error: 'No error', RadarState_Temporary_Error: 'No error', RadarState_Voltage_Error: 'No error', RadarState_RadarPowerCfg: 'Standard', RadarState_SortIndex: 'Sorted by range', RadarState_SensorID: 'ID 0', RadarState_MotionRxState: 'Speed and yaw rate missing', RadarState_SendExtInfoCfg: 'Active', RadarState_SendQualityCfg: 'Active', RadarState_OutputTypeCfg: 'SendObjects', RadarState_CtrlRelayCfg: 'Inactive', RadarState_RCS_Threshold: 'Standard')
  can1  700   [4]  04 1E 01 00 :: VersionID(Version_MajorRelease: 4, Version_MinorRelease: 30, Version_PatchLevel: 1, Version_ExtendedRange: 'Standard Range 196m-260m', Version_CountryCode: 'International Version')
  can1  60A   [4]  03 E4 8D 10 :: Obj_0_Status(Obj_NofObjects: 3, Obj_MeasCounter: 58509, Obj_InterfaceVersion: 1)
  can1  60B   [8]  06 4E 94 00 80 20 01 93 :: Obj_1_General(Obj_ID: 6, Obj_DistLong: 2.8000000000000114 m, Obj_DistLat: 0.20000000000001705 m, Obj_VrelLong: 0.0 m/s, Obj_VrelLat: 0.0 m/s, Obj_DynProp: 'Stationary', Obj_RCS: 9.5 dBm²)
  can1  60B   [8]  00 4E B4 1B 80 20 01 90 :: Obj_1_General(Obj_ID: 0, Obj_DistLong: 3.6000000000000227 m, Obj_DistLat: 5.600000000000023 m, Obj_VrelLong: 0.0 m/s, Obj_VrelLat: 0.0 m/s, Obj_DynProp: 'Stationary', Obj_RCS: 8.0 dBm²)
  can1  60B   [8]  01 4F 34 03 80 20 01 68 :: Obj_1_General(Obj_ID: 1, Obj_DistLong: 6.800000000000011 m, Obj_DistLat: 0.8000000000000114 m, Obj_VrelLong: 0.0 m/s, Obj_VrelLat: 0.0 m/s, Obj_DynProp: 'Stationary', Obj_RCS: -12.0 dBm²)
  can1  60C   [7]  06 84 A3 3A 02 20 E8 :: Obj_2_Quality(Obj_ID: 6, Obj_DistLong_rms: '<0.288 m', Obj_DistLat_rms: '<0.478 m', Obj_VrelLong_rms: '<0.371 m/s', Obj_VrelLat_rms: '<0.616 m/s', Obj_ArelLong_rms: '<0.794 m/s²', Obj_ArelLat_rms: '<0.005 m/s²', Obj_Orientation_rms: '<1.909 deg', Obj_ProbOfExist: '<=100%', Obj_MeasState: 'Measured')
  can1  60C   [7]  00 8C A7 3A 82 20 E8 :: Obj_2_Quality(Obj_ID: 0, Obj_DistLong_rms: '<0.371 m', Obj_DistLat_rms: '<0.478 m', Obj_VrelLong_rms: '<0.616 m/s', Obj_VrelLat_rms: '<0.616 m/s', Obj_ArelLong_rms: '<1.023 m/s²', Obj_ArelLat_rms: '<0.005 m/s²', Obj_Orientation_rms: '<1.909 deg', Obj_ProbOfExist: '<=100%', Obj_MeasState: 'Measured')
  can1  60C   [7]  01 7C 61 3A 02 20 E8 :: Obj_2_Quality(Obj_ID: 1, Obj_DistLong_rms: '<0.224 m', Obj_DistLat_rms: '<0.371 m', Obj_VrelLong_rms: '<0.288 m/s', Obj_VrelLat_rms: '<0.616 m/s', Obj_ArelLong_rms: '<0.794 m/s²', Obj_ArelLat_rms: '<0.005 m/s²', Obj_Orientation_rms: '<1.909 deg', Obj_ProbOfExist: '<=100%', Obj_MeasState: 'Measured')
  can1  60D   [8]  06 7D 0F A1 70 80 0E 0C :: Obj_3_Extended(Obj_ID: 6, Obj_ArelLong: 0.0 m/s², Obj_ArelLat: 0.0 m/s², Obj_Class: 'Car', Obj_OrientationAngle: 0.0 deg, Obj_Length: 2.8000000000000003 m, Obj_Width: 2.4000000000000004 m)
  can1  60D   [8]  00 7D 0F A0 70 80 05 05 :: Obj_3_Extended(Obj_ID: 0, Obj_ArelLong: 0.0 m/s², Obj_ArelLat: 0.0 m/s², Obj_Class: 'Point', Obj_OrientationAngle: 0.0 deg, Obj_Length: 1.0 m, Obj_Width: 1.0 m)
  can1  60D   [8]  01 7D 0F A6 70 80 16 0B :: Obj_3_Extended(Obj_ID: 1, Obj_ArelLong: 0.0 m/s², Obj_ArelLat: 0.0 m/s², Obj_Class: 'Wide', Obj_OrientationAngle: 0.0 deg, Obj_Length: 4.4 m, Obj_Width: 2.2 m)
  

其中可以看出:

  • 0x201中的RadarState_MotionRxState: ‘Speed and yaw rate missing’, 说明没有输入车速和yawrate
  • 0x700看到版本号为4.30.1, 标准距离(非1200m扩展距离版本), 国际版本(不是功率较低的日韩版本)

如果只想看状态信息, 并且不要单行模式, 加个滤波:

$ candump can1,201:7FF,700:7FF | cantools decode -m 0x201 -m 0x700 --no-strict ARS408_id0.dbc

  can1  201   [8]  C0 19 00 00 10 F4 00 00 ::
RadarState(
    RadarState_NVMwriteStatus: 1,
    RadarState_NVMReadStatus: 'successful',
    RadarState_MaxDistanceCfg: 200 m,
    RadarState_Persistent_Error: 'No error',
    RadarState_Interference: 'No interference',
    RadarState_Temperature_Error: 'No error',
    RadarState_Temporary_Error: 'No error',
    RadarState_Voltage_Error: 'No error',
    RadarState_RadarPowerCfg: 'Standard',
    RadarState_SortIndex: 'Sorted by range',
    RadarState_SensorID: 'ID 0',
    RadarState_MotionRxState: 'Speed and yaw rate missing',
    RadarState_SendExtInfoCfg: 'Active',
    RadarState_SendQualityCfg: 'Active',
    RadarState_OutputTypeCfg: 'SendObjects',
    RadarState_CtrlRelayCfg: 'Inactive',
    RadarState_RCS_Threshold: 'Standard'
)
  can1  700   [4]  04 1E 01 00 :: unpack requires at least 40 bits to unpack (got 32)

这里0x700没有被解析出来, 可能那里没有配置好或者软件bug.

写个脚本看最大距离和版本信息:

import can
import cantools
from pprint import pprint
import binascii

db = cantools.database.load_file('ARS408_id0.dbc')

# for i in range(len(db.messages)):
#     print(db.messages[i])
RadarState_message = db.get_message_by_name('RadarState')
VersionID_message = db.get_message_by_name('VersionID')

# pprint(RadarConfiguration_message.signals)
can_bus = can.interface.Bus(bustype='socketcan', channel='can1', bitrate=500000)

while True:
    message = can_bus.recv()

    # if message.arbitration_id == 0x201:
    if message.arbitration_id == RadarState_message.frame_id:
        print(hex(message.arbitration_id),\
              len(message.data),\
              binascii.hexlify(message.data),\
              'MaxDistance: ',\
              db.decode_message(message.arbitration_id,message.data).get('RadarState_MaxDistanceCfg'))

    #elif message.arbitration_id == 0x700:
    elif message.arbitration_id == VersionID_message.frame_id:
        dic = db.decode_message(message.arbitration_id, message.data)
        print(hex(message.arbitration_id),\
              len(message.data),\
              binascii.hexlify(message.data),\
              'Version:',\
              str(dic.get('Version_MajorRelease'))+'.'+\
              str(dic.get('Version_MinorRelease'))+'.'+\
              str(dic.get('Version_PatchLevel')))    

运行结果如下:

$ python3 2.py
0x201 8 b'4019000010f40000' MaxDistance:  200
0x700 4 b'041e0100' Version: 4.30.1
0x201 8 b'4019000010f40000' MaxDistance:  200
0x700 4 b'041e0100' Version: 4.30.1

YawRate与车速输入

以50ms发送示例:

import can
import cantools
from pprint import pprint
import binascii
import time

db = cantools.database.load_file('ARS408_id0.dbc')

SpeedInformation_message = db.get_message_by_name('SpeedInformation')
YawRateInformation_message = db.get_message_by_name('YawRateInformation')

def msg_periodic_send(bus):
    SpeedInformation_canmsg = can.Message(
        arbitration_id=SpeedInformation_message.frame_id,\
        data=[],\
        is_extended_id=False
    )

    YawRateInformation_canmsg = can.Message(
        arbitration_id=YawRateInformation_message.frame_id,\
        data=[],\
        is_extended_id=False
    )

    SpeedInformation_task = bus.send_periodic(SpeedInformation_canmsg, 0.050)
    if not isinstance(SpeedInformation_task, can.ModifiableCyclicTaskABC):
        print("This interface doesn't seem to support modification")
        SpeedInformation_task.stop()
        return
    
    YawRateInformation_task = bus.send_periodic(YawRateInformation_canmsg, 0.050)
    if not isinstance(SpeedInformation_task, can.ModifiableCyclicTaskABC):
        print("This interface doesn't seem to support modification")
        YawRateInformation_task.stop()
        return

    temp_speed = 0 # km/h->m/s    
    while True:
        time.sleep(0.05)

        # Modify Data Here
        temp_speed += 1
        print(temp_speed,'km/h -> ', '%.1f' % (temp_speed*1000.0/3600), 'm/s')
        if (temp_speed > 163.8*3600/1000):
            temp_speed = 0
        
        # 0:'standstill', 1:'forward', 2:'reverse', 3:'reserved'
        SpeedInformation_data = SpeedInformation_message.encode({\
                                'RadarDevice_SpeedDirection': 'forward',\
                                'RadarDevice_Speed': temp_speed*1000.0/3600})
        YawRateInformation_data = YawRateInformation_message.encode({\
                                'RadarDevice_YawRate': 0})

        SpeedInformation_canmsg.data[:] = SpeedInformation_data[:]
        SpeedInformation_canmsg.dlc = len(SpeedInformation_canmsg.data)
        YawRateInformation_canmsg.data[:] = YawRateInformation_data[:]
        YawRateInformation_canmsg.dlc = len(SpeedInformation_canmsg.data)

        SpeedInformation_task.modify_data(SpeedInformation_canmsg)
        YawRateInformation_task.modify_data(YawRateInformation_canmsg)

    # task.stop()

if __name__ == "__main__":
    can_bus = can.interface.Bus(bustype='socketcan', channel='can1', bitrate=500000)
    msg_periodic_send(can_bus)

运行这个帧后就可以看到发出来0x300/0x3012字节, 50ms周期的帧, 在0x201这个帧里面可以看状态, 直接写脚本解析这个状态:

import can
import cantools
import binascii

db = cantools.database.load_file('ARS408_id0.dbc')
RadarState_message = db.get_message_by_name('RadarState')
can_bus = can.interface.Bus(bustype='socketcan', channel='can1', bitrate=500000)

while True:
    message = can_bus.recv()
    if message.arbitration_id == RadarState_message.frame_id:
        print(hex(message.arbitration_id),\
              len(message.data),\
              binascii.hexlify(message.data),\
              'RadarState_MotionRxState: ',\
              db.decode_message(message.arbitration_id,message.data).get('RadarState_MotionRxState'))

运行:

$ python3 3.py
1 km/h ->  0.3 m/s
2 km/h ->  0.6 m/s
3 km/h ->  0.8 m/s

$ python3 4.py
0x201 8 b'4019000010f40000' RadarState_MotionRxState:  Speed and yaw rate missing
0x201 8 b'4019000010f40000' RadarState_MotionRxState:  Speed and yaw rate missing
0x201 8 b'4019000010f40000' RadarState_MotionRxState:  Speed and yaw rate missing
0x201 8 b'4019000010340000' RadarState_MotionRxState:  Input ok
0x201 8 b'4019000010340000' RadarState_MotionRxState:  Input ok

当速度大于115m/s(414 km/h )时, 60A输出目标0, 60B,60C,60D将停止输出.

录包回放

can.logger是 pip 安装 python-can 包自带的.

录包:

# 全录, 存为1.log
$ python3 -m can.logger -f 1.log -c can1 -i socketcan
Connected to SocketcanBus: socketcan channel 'can1'
Can Logger (Started on 2021-06-11 17:18:22.170566)
# log文件大概写满这个样子
# (1623403102.177979) can1 60A#01962B10
# (1623403102.180162) can1 60B#014E93FF80200194
# (1623403102.180669) can1 60C#0184A33A8220E8
# (1623403102.180988) can1 60D#017D0FA070800505
    
# 全录, 存为2.asc
$ python3 -m can.logger -f 2.asc -c can1 -i socketcan
Connected to SocketcanBus: socketcan channel 'can1'
Can Logger (Started on 2021-06-11 17:19:50.655305)
# asc文件的格式如下: 
# date Fri Jun 06 05:19:50.656751 PM 2021
# base hex  timestamps absolute
# internal events logged
# Begin Triggerblock Fri Jun 06 05:19:50.707 PM 2021
#  0.000000 Start of measurement
#  0.000000 2  60A             Rx   d 4 01 9F C3 10
#  0.004938 2  60B             Rx   d 8 01 4E 93 FF 80 20 01 94
#  0.005491 2  60C             Rx   d 7 01 84 A3 3A 82 20 E8
#  0.005878 2  60D             Rx   d 8 01 7D 0F A0 70 80 05 05

# 只录某几个ID, 如60A,60B
$ python3 -m can.logger -f 3.log -c can1 -i socketcan --filter 60A:7FF 60B:7FF
Adding filter/s ['60A:7FF', '60B:7FF']
Connected to SocketcanBus: socketcan channel 'can1'
Can Logger (Started on 2021-06-11 17:23:09.158519)

can.player是 pip 安装 python-can 包自带的.

回放:

$ python3 -m can.player -c can1 -i socketcan 1.log
Can LogReader (Started on 2021-06-11 17:27:45.413390)

# 回放出的时间间隔也大致对得上
$ candump -td -x can1
 (000.000000)  can1  TX - -  60A   [4]  01 96 2B 10
 (000.001688)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000801)  can1  TX - -  60C   [7]  01 84 A3 3A 82 20 E8
 (000.000908)  can1  TX - -  60D   [8]  01 7D 0F A0 70 80 05 05
 (000.069121)  can1  TX - -  60A   [4]  01 96 2D 10
 (000.000691)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000464)  can1  TX - -  60C   [7]  01 84 A3 3A 82 20 E8
 (000.002162)  can1  TX - -  60D   [8]  01 7D 0F A0 70 80 05 05
 
 # asc回放
 $ python3 -m can.player -c can1 -i socketcan 2.asc
Can LogReader (Started on 2021-06-11 17:30:06.607237)

# 快速回放, 不按时间戳, 一溜烟发出来
$ python3 -m can.player -c can1 -i socketcan 3.log --ignore-timestamps
Can LogReader (Started on 2021-06-11 17:31:39.144332)

# 可以看到基本上是
$ candump -td -x can1
 (000.000000)  can1  TX - -  60A   [4]  01 B5 43 10
 (000.003569)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000982)  can1  TX - -  60A   [4]  01 B5 45 10
 (000.000653)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000414)  can1  TX - -  60A   [4]  01 B5 47 10
 (000.000411)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000320)  can1  TX - -  60A   [4]  01 B5 49 10
 (000.000447)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 (000.000384)  can1  TX - -  60A   [4]  01 B5 4B 10
 (000.000512)  can1  TX - -  60B   [8]  01 4E 93 FF 80 20 01 94
 
 # 可以看下总线负载率
 $ canbusload can1@500000

DBC下载

ARS408_id0.dbc

参考

微信公众号

欢迎扫描二维码关注本人微信公众号, 及时获取最新文章:
在这里插入图片描述

  • 29
    点赞
  • 218
    收藏
    觉得还不错? 一键收藏
  • 16
    评论
评论 16
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值