Apollo-canbus的板块分析


目录

  • Apollo的D-KIT 自动驾驶开发套件
  • 概述:
  • CANBUS在整个自动驾驶模块的系统的功能概述
  • CAN报文的读写与解析
  • motorola格式
  • motorola格式的存储方式
  • can报文中的数据排列方式
  • dbc文件的一帧报文的字段含义
  • can报文原始值与实际的物理值的转化
  • can报文原始值与实际的物理值的转化的结果验证
  • apollo中的can协议的解析
  • 单个字节中获取对应的位原始数据
  • 跨字节的原始数据的获取
  • 以steering_report(canID:502)为例分析
  • Apollo的底盘反馈信息
  • Apollo将反馈信息赋值给protobuf的uml
  • apollo代码目录
  • devkit整车的详细信息如下:


Apollo的D-KIT 自动驾驶开发套件

概述:

Apollo D-KIT 自动驾驶开发套件是 Apollo 推出的全球首款自动驾驶开发套件,包含适配 Apollo 开源软件的线控底盘及整套传感器硬件。软硬车云一体,帮助开发者快速进入算法实车验证,加速自动驾驶研发进程。

具体的车型图片为:

apollo 不用refreshscope apollo canbus_数据


此外可以去看看apollo的开发套件的介绍网址:Apollo D-KIT 还有其他车型的网址:与Apollo兼容的开发车型

CANBUS在整个自动驾驶模块的系统的功能概述

画一个简单的车辆底盘的网络架构图,简单的就是各种ECU会发对应的CANID以及数据,经过VCU的处理以及隔离,将有的ECU的数据进行合并为新的一帧can报文,并以不同的CANID进行反馈出来,当域控制器接受到VCU发布的CAN帧进行解析为其他数据形式,如protobuf或者ros等格式,我们接触到的DBC文件实际上是与VCU之间的通信帧,VCU与底盘的硬件通信我们无需关心,跟车企有关。而当顶层域控制器(工控机)发送控制指令给VCU时,VCU会根据发来的数据以及ID,根据一定的逻辑再转换到底盘。中间有一层VCU作为隔离,大大增加车辆的安全性。

apollo 不用refreshscope apollo canbus_自动驾驶_02

can网络中的数据是以报文的形式来进行传递的,包含canId,can数据的长度以及数据
以下为linux下采用SocketCAN通信时,在#include <linux/can.h>中定义的can_frame中的结构体

can_id: 这是一个32位的字段,用于存储CAN帧的标识符。在扩展帧格式(EFF)中,它可以 包含29位的标识符,在标准帧格式(SFF)中,则是11位。此外,can_id还可能包含一些标志位,如错误帧标志和远程传输请求(RTR)标志。

can_dlc: 这是一个字节大小的字段,表示数据字段中的字节数。它的值范围从0到8,因为在经典CAN协议中,一个帧的数据长度最多只能有8字节,一般都是8个字节填充满传输。

__pad, __res0, __res1: 这些字段用于确保结构体的总大小和对齐是正确的,但它们自身不携带任何意义。

data: 这是一个长度为8字节的数组,包含了帧的有效载荷数据。

apollo 不用refreshscope apollo canbus_自动驾驶_03

CAN报文的读写与解析

Apollo通过CanBus节点,将上层域控制器中软件发布的Protobuf信息(也就是对应着apollo中的control_cmd.proto信息)转化为CAN报文(对应着#include <linux/can.h>中定义的can_frame)发送给底盘,将底盘反馈的CAN报文信息转化为protobuf信息(即:chassis.proto )给到域控制器中的上层软件

apollo 不用refreshscope apollo canbus_数据_04

motorola格式

motorola格式的存储方式

motorola格式采用的是大端的形式,即低地址存储高字节,高地址存储低字节的数据

apollo 不用refreshscope apollo canbus_数据_05

can报文中的数据排列方式

以下为三个信号的用Vector CANdb++打开的 layout,很明显的看出是大端模式

Motorola格式是一种大端序(Big Endian)的数据表示方式,其中高字节在前,低字节在后。在Motorola格式中,多字节数据的最高有效字节(MSB)存储在内存中的最低地址处,而最低有效字节(LSB)存储在内存中的最高地址处

apollo 不用refreshscope apollo canbus_自动驾驶_06

dbc文件的一帧报文的字段含义

下面我们以一个Message(IMU的角速度的报文)作为一个例子进行分析

报文的CanId为0x321,报文的详细的数据开始字节以及长度以及排列方式,精度(factor)以及偏移(offset)等如下图

apollo 不用refreshscope apollo canbus_数据_07

Message:关键字,表示消息,一帧报文
Signal : 信号名称 “Startbit”: 起始位
Length[Bit]:信号长度,单位为:bit
ByteOrder:字节顺序,0 ——> Motorola格式,1 ——>Inter格式
valueType: 信号的数值类型,‘+’ ——> ‘无符号数’, ‘-’ ——> ‘有符号数’
Factor:表示因子, “Offset”:偏移量
物理值 = 原始值 * Factor + Offset
"Minimum: 信号的最小值,为double类型 “Maximum”:信号的最大值,为double类型 “Unit”:
该信号的单位,为字符串类型

can报文原始值与实际的物理值的转化

下面就来详细的说一下can报文值转化为实际的我们比较直观的物理值

根据motorola跨字节的存储方式,我们要解析每个信号所代表的实际的物理含义

表格中提供了当前canId所携带的数据,并转化为二进制

根据表格中提供的开始位,以及所占位的长度以及排序方式,我们得到每个占用20位数据的HEX以及BIN,将can报文的原始值转化为实际的物理值得公式如下

apollo 不用refreshscope apollo canbus_原始数据_08(将can报文的原始数据转化为实际的物理值)

以第一个apollo 不用refreshscope apollo canbus_原始数据_09 为例apollo 不用refreshscope apollo canbus_原始数据_10

当需要将实际得物理值转换为can报文的原始值公式如下

apollo 不用refreshscope apollo canbus_数据_11 (将物理值转化为can报文原始值)

apollo 不用refreshscope apollo canbus_原始数据_12

can报文原始值与实际的物理值的转化的结果验证

这个是采用ZCanPRO软件打开的dbc文件,这个软件功能较多,我们这里用于验证一下输入的8个字节的can原始数据得到实际值的物理,反之,输入实际的物理值与得到的8个字节的can原始数据 是否与我们手动计算的一致。

apollo 不用refreshscope apollo canbus_自动驾驶_13

apollo中的can协议的解析

接下来我们来看代码中是如何解析can数据转化为apollo数据的
现在我们看Byte.h以及byte.cc中的这个类是如何对单个字节进行操作的

下面两个随意定义的两个信号,用于演示,New_Signal_001,以及New_Signals_002的信号布局图

apollo 不用refreshscope apollo canbus_数据_14

假设这两个字节当前的车辆底盘上传的数据为:

apollo 不用refreshscope apollo canbus_自动驾驶_15

单个字节中获取对应的位原始数据

第0个字节中的原始数据,value_ = 0xB5 = 0B10110101,现在要获取起始位[startBit]=2,以及占位长度length[Bit]=4的数据0x0D
操作步骤如下:

  • [1] 将原始的字节右移起始位为result ,0xB5 << 2
  • [2] 创建一个掩码变量const uint8_t RANG_MASK_1_L[] = {0x01, 0x03, 0x07, 0x0F, 0x1F, 0x3F, 0x7F,0xFF};
  • [3] 根据占位长度取出掩码变量集中的一个 RANG_MASK_1_L[length[Bit]-1],即RANG_MASK_1_L[3]==0x0F
  • [4] 将掩码0x0F与result进行与运算,即result &= RANG_MASK_1_L[real_len - 1]
  • [ 5] 最终得到结果为0B1101 == 0x0D

跨字节的原始数据的获取

访问消息中New_Signals_002的信号,他的Startbit = 20,length[Bit] = 12.

apollo 不用refreshscope apollo canbus_原始数据_16


首先操作byte2的数据value_ = 0xA5 = 0B10100101,现在要获取起始位[startBit]=4,以及占位长度length[Bit]=4的数据0x0A

操作步骤如下:

  • [1] 将原始的字节右移起始位为result ,0xA5 << 4
  • [2] 创建一个掩码变量const uint8_t RANG_MASK_1_L[] = {0x01, 0x03, 0x07, 0x0F, 0x1F, 0x3F, 0x7F,0xFF};
  • [3] 根据占位长度取出掩码变量集中的一个 RANG_MASK_1_L[length[Bit]-1],即RANG_MASK_1_L[3]==0x0F
  • [4] 将掩码0x0F与result进行与运算,即result &= RANG_MASK_1_L[real_len - 1]
  • [ 5] 最终得到结果为0B00001010 == 0x0A

    我们上面将的是mororolo格式,motorolo跟intel的格式的区别就是在这里了,就是跨字节后的高低字节的组合,我们这里以motorolo格式位例子
    byte1也可以按照上面的方式进行操作,也可以直接拿byte1的数据去合并byte2中的该signal的有效位的数据:
  • [6] 将获取到的第2个字节中的部分位以及第一字节的整个8位都赋值给一个int16或者int32或者int64,防止移位操作时越界;
  • [7]根据motorolo的格式,将两个字节的数据进行合并,将第一个字节左移,左移长度为byte2中的对于该变量的有效位,byte1<<4;
  • [8] 将左移动之后的byte1与byte2进行"或"运算,得到最终的结果result = 0x1DA

以steering_report(canID:502)为例分析

这里将一下将如何利用dbc将对应的signal进行拆分,这里以apollo中的modules/canbus_vehicle/devkit/protocol/steering_report_502.cc为例进行分析,这个devtik的开发套件的地盘正好是Motorola格式,具体的intel格式自行了解,只有在跨字节时有少许区别。

首先在解释之前,我是觉得他生成的config detail是有问题的,我就手动按照他的代码做了一帧转向的dbc,结果当我用Zcanpro打开时,发现跟他的config detil是一致的(有点尴尬,看不懂),zcanpro这里之前一直没关注,只是偶尔看到了报文不想自己手动算,就直接带入或者模拟发送数据

这里根据代码,我制作了该帧的message,并且添加了steering_report_502.cc中代码的所有的signals。

apollo 不用refreshscope apollo canbus_原始数据_17


现在展开该帧message中各个siganl的Layout

apollo 不用refreshscope apollo canbus_自动驾驶_18


现在假设传入的can的原始数据为:

uint8 data[8]={0x02 , 0x01,0x00,0x02,0x12,0x01,0xF4,0x1E}

从上面的图中可以看出,对于siagnl中的[Steer_en_state]字段中, StartBit = 0 ,length[Bit] = 2;那我们能判定该信号位于第一字节,那么我们将第0个字节的数据拿出 uint8 byte1 = 0x02== 0B0000 0010,取其中的第0位到第1位的数据x = 0x10

uint8_t Byte::get_byte(const int32_t start_pos, const int32_t length) const {
  if (start_pos > BYTE_LENGTH - 1 || start_pos < 0 || length < 1) {
    return 0x00;
  }
  int32_t end_pos = std::min(start_pos + length - 1, BYTE_LENGTH - 1);
  int32_t real_len = end_pos + 1 - start_pos;
  uint8_t result = static_cast<uint8_t>(*value_ >> start_pos);
  result &= RANG_MASK_1_L[real_len - 1];
  return result;
}

这里就是直接获取第0个字节的数据,然后取的开始位为0,长度为2

apollo 不用refreshscope apollo canbus_自动驾驶_19

[Steer_angle_actual]该signal的开始位[startbit]为32,占用的长度[Length[Bit]]=16

①获取第3个字节的整个字节的数据 x = 0x02

②获取第4个字节的整个字节的数据 t = 0x12

③将第3个字节右移8位,并且与第4字节“或”运算,进行合并 x = 0x0212

④将获取到的原始值换算为物理值

物理值 = 原始值 * Factor + Offset

apollo 不用refreshscope apollo canbus_数据_20

这是用ZCANPRO打开的效果,自己可以试着带入这些字节数据,解析之后,查看一下各个signal是否跟下面一致。

apollo 不用refreshscope apollo canbus_自动驾驶_21

Apollo的底盘反馈信息

Apollo将反馈信息赋值给protobuf的uml

整车的控制信息—>can报文,以及can报文信息转化为–>protobuf的信息,简单的uml类图如下。

apollo 不用refreshscope apollo canbus_数据_22


每个report都中都有个Parse函数,将该id对应的报文解析为物理值,赋值给protobuf中的变量,这样就可以获取整车的详细信息

apollo 不用refreshscope apollo canbus_数据_23

apollo代码目录

在moudules/canbus_vehicle/devkit/protocol/的目录下一些文件命名为格式为xxxx_command_CanId.cpp,是将protobuf中的信息转化为uint8*的can_frame中的uint data[8],并且里面也定义了canID,canID以及数据都有了,就可以赋值给can_frame,经过SocketCAN通信传递给底盘
一些命名为xxx_report_CanId.cpp,是将socketCan信息中的can_frame,转化为protobuf中的信息。

modules/canbus_vehicle/
└── devkit                                 // devkit车型协议及车辆控制等实现文件
    ├── BUILD                               // 构建规则文件
    ├── cyberfile.xml                       // 包管理配置文件
    ├── devkit_controller.cc               //devkit车型控制器实现文件
    ├── devkit_controller.h                // devkit车型控制器声明文件
    ├── devkit_controller_test.cc          // devkit车型控制器单元测试文件
    ├── devkit_message_manager.cc          // devkit车型发送/接收报文管理器实现文件
    ├── devkit_message_manager.h           //devkit车型发送/接收报文管理器声明文件
    ├── devkit_message_manager_test.cc     // devkit车型发送/接收报文管理器单元测试文件
    ├── devkit_vehicle_factory.cc          // devkit车型车型工厂实现文件
    ├── devkit_vehicle_factory.h           // devkit车型车型工厂声明文件
    ├── devkit_vehicle_factory_test.cc     // devkit车型车型工厂单元测试文件
    ├── docs/                               // 说明文档相关文件
    ├── README_cn.md                        // 包说明文档
    ├── proto/                              // 车型协议变量定义文件夹
    │   ├── BUILD                           // 构建规则文件
    │   └── devkit.proto                   // lincoln车型协议变量类型定义文件
    ├── protocol/                           // 协议解析实现文件夹
    │   ├── bms_report_512.cc                     // BMS电源报文反馈协议解析实现文件
    │   ├── bms_report_512.h                      // BMS电源报文反馈协议解析实现文件
    │   ├── bms_report_512_test.cc                // BMS电源报文反馈协议解析单元测试文件
    │   ├── brake_command_101.cc                     // 制动报文控制协议解析实现文件
    │   ├── brake_command_101.h                      // 制动报文控制协议解析实现文件
    │   ├── brake_command_101_test.cc                // 制动报文控制协议解析单元测试文件
    │   .
    │   .
    │   .
    └── testdata                            // 单元测试测试数据文件夹

devkit整车的详细信息如下:

***devkit.proto ***

syntax = "proto2";

package apollo.canbus;

//********【begin】 这一部分的控制信息,也就是底盘的横向控制以及纵向控制的控制指令*************//
message Throttle_command_100 {  //纵向控制指令的结构体,id为:0X100
// Control Message
  enum Throttle_en_ctrlType {     //驱动(油门)的使能信号
    THROTTLE_EN_CTRL_DISABLE = 0; //油门使能
    THROTTLE_EN_CTRL_ENABLE = 1;  //油门不使能
  }
  // [m/s^2] [0|10]                  //车辆的目标纵向加速度的单位[m/s^2],范围[0,10]
  optional double throttle_acc = 1;  //车辆目标纵向加速度
  // [] [0|255]
  optional int32 checksum_100 = 2;   //驱动控制信号数据校验checksum  
  // [%] [0|100]
  optional double throttle_pedal_target = 3; //虚拟目标加速踏板位置
  // [] [0|1]
  optional Throttle_en_ctrlType throttle_en_ctrl = 4;//驱动使能
  // [m/s] [0|10.23]
  optional double speed_target = 5;  //目标车速
}

message Brake_command_101 {       //制动控制指令
// Control Message
  enum Aeb_en_ctrlType {         //AEB(Automatic Emergency Braking System)制动模式 枚举
    AEB_EN_CTRL_DISABLE_AEB = 0; //AEB控制不使能
    AEB_EN_CTRL_ENABLE_AEB = 1;  //AEB控制使能
  }
  enum Brake_en_ctrlType {       //制动控制使能位
    BRAKE_EN_CTRL_DISABLE = 0;   //制动控制不使能
    BRAKE_EN_CTRL_ENABLE = 1;    //制动控制使能
  }
  // [m/s^2] [0|10]              //减速度单位[m/s^2],减速度的范围[0,10]
  optional double brake_dec = 1; //目标减速度
  // [] [0|255]
  optional int32 checksum_101 = 2;//制动控制信号数据校验checksum
  // [%] [0|100]
  optional double brake_pedal_target = 3;//制动踏板的目标位置
  // [] [0|1]
  optional Brake_en_ctrlType brake_en_ctrl = 4;//制动使能位的控制
  // [] [0|0]
  optional Aeb_en_ctrlType aeb_en_ctrl = 5;//AEB的控制使能位
}

message Steering_command_102 {    //横向控制指令的结构体
// Control Message
  enum Steer_en_ctrlType {        //转向控制控制位的 枚举
    STEER_EN_CTRL_DISABLE = 0;    //转向控制使能有效
    STEER_EN_CTRL_ENABLE = 1;     //转向控制使能无效
  }
  // [] [0|1]
  optional Steer_en_ctrlType steer_en_ctrl = 1; //转向控制位使能
  // [deg] [-500|500]                           //这里的单位是角度不是弧度
  optional int32 steer_angle_target = 2;        //目标方向盘转角
  // [deg/s] [0|250]
  optional int32 steer_angle_spd_target = 3;    //目标方向盘转速
  // [] [0|255]
  optional int32 checksum_102 = 4;              //转向控制信号数据校验checksum
}

message Gear_command_103 {    //档位控制消息结构体,CanID:0X103
// Control Message
  enum Gear_targetType {      //目标档位枚举
    GEAR_TARGET_INVALID = 0;  //档位无效
    GEAR_TARGET_PARK = 1;     //驻车档
    GEAR_TARGET_REVERSE = 2;  //倒车挡
    GEAR_TARGET_NEUTRAL = 3;  //空挡
    GEAR_TARGET_DRIVE = 4;    //前进挡
  }
  enum Gear_en_ctrlType {     //档位使能枚举
    GEAR_EN_CTRL_DISABLE = 0; //档位控制使能无效
    GEAR_EN_CTRL_ENABLE = 1;  //档位控制使能有效
  }
  // [] [0|4]
  optional Gear_targetType gear_target = 1;  //目标档位
  // [] [0|1]
  optional Gear_en_ctrlType gear_en_ctrl = 2;//档位使能
  // [] [0|255]
  optional int32 checksum_103 = 3;           //档位控制信号数据校验checksum
}

message Park_command_104 { //驻车控制消息的结构体
// Control Message
  enum Park_targetType {             //驻车请求        
    PARK_TARGET_RELEASE = 0;         //解除驻车
    PARK_TARGET_PARKING_TRIGGER = 1; //驻车
  }
  enum Park_en_ctrlType {        //驻车控制使能  
    PARK_EN_CTRL_DISABLE = 0;    //驻车控制使能无效 
    PARK_EN_CTRL_ENABLE = 1;     //驻车控制使能有效
  }
  // [] [0|255]
  optional int32 checksum_104 = 1;           //驻车控制信号数据校验checksum
  // [] [0|1]
  optional Park_targetType park_target = 2;  //驻车的请求
  // [] [0|1]
  optional Park_en_ctrlType park_en_ctrl = 3;//驻车使能的控制
}

message Vehicle_mode_command_105 { //车辆模式的控制消息结构体
// Control Message
  enum Turn_light_ctrlType {                         //用于控制车辆转向灯的枚举变量    
    TURN_LIGHT_CTRL_TURNLAMP_OFF = 0;                //转向灯关闭
    TURN_LIGHT_CTRL_LEFT_TURNLAMP_ON = 1;            //左转向打开
    TURN_LIGHT_CTRL_RIGHT_TURNLAMP_ON = 2;           //右转向打开
    TURN_LIGHT_CTRL_HAZARD_WARNING_LAMPSTS_ON = 3;   //危险警告灯打开
  }
  enum Vin_reqType {             //车辆控制识别号的枚举变量                  
    VIN_REQ_VIN_REQ_DISABLE = 0; //禁用车辆识别号请求
    VIN_REQ_VIN_REQ_ENABLE = 1;  //启用车辆识别号请求
  }
  enum Drive_mode_ctrlType {                   //驱动模式的控制类型
    DRIVE_MODE_CTRL_THROTTLE_PADDLE_DRIVE = 0; //油门模式(定义为油门模式时,车辆只会响应油门指令)
    DRIVE_MODE_CTRL_SPEED_DRIVE = 1;           //速度模式(定义为速度模式时,车辆只会响应速度指令)
  }
  enum Steer_mode_ctrlType {                 //转向控制模式
    STEER_MODE_CTRL_STANDARD_STEER = 0;      //转向的标准模式
    STEER_MODE_CTRL_NON_DIRECTION_STEER = 1; //非定向转向模式 (不用管,一般也不会用)
    STEER_MODE_CTRL_SYNC_DIRECTION_STEER = 2;//同步定向模式(一些定速巡航需要吧,也不知道,别管)
  }
  // [] [0|255]
  optional int32 checksum_105 = 1; //数据校验
  // [] [0|7]
  optional Turn_light_ctrlType turn_light_ctrl = 2;
  // [] [0|1]
  optional Vin_reqType vin_req = 3;
  // [] [0|7]
  optional Drive_mode_ctrlType drive_mode_ctrl = 4; //驱动模式
  // [] [0|7]
  optional Steer_mode_ctrlType steer_mode_ctrl = 5; //转向模式
}
//********【end】 这一部分的控制信息,也就是底盘的横向控制以及纵向控制的控制指令*************//


//********【begin】 这一部分反馈信息,也就是底盘的ecu的状态通过vcu反馈给ipc*************//
message Throttle_report_500 {   
// Report Message
  enum Throttle_flt2Type {                             //驱动系统通信的超时枚举
    THROTTLE_FLT2_NO_FAULT = 0;                        //无故障
    THROTTLE_FLT2_DRIVE_SYSTEM_COMUNICATION_FAULT = 1; //驱动系统通信超时故障
  }
  enum Throttle_flt1Type {                             //驱动系统的故障信息
    THROTTLE_FLT1_NO_FAULT = 0;                        //无故障
    THROTTLE_FLT1_DRIVE_SYSTEM_HARDWARE_FAULT = 1;     //驱动系统的硬件故障(一般指的是电机故障)
  }

  //******
  自动驾驶模式(AUTO):车辆底盘接收到使能信号后,进入自动驾驶模式。
  被接管(TAKE_OVER):车辆底盘在自动驾驶模式下被动退出自动驾驶模式,并进入到工人驾驶模式称为被接管。
  人工模式(MANUAL):人工驾驶模式下,车辆可以被驾驶员操作,也可以处于等待进入自动驾驶的状态,车辆等待接收自动驾驶使能信号,或接收人工驾驶指令信号
  *******//
  enum Throttle_en_stateType {    //驱动系统的模式枚举
    THROTTLE_EN_STATE_MANUAL = 0;   //手动模式
    THROTTLE_EN_STATE_AUTO = 1;     //自动模式
    THROTTLE_EN_STATE_TAKEOVER = 2; //接管模式
    THROTTLE_EN_STATE_STANDBY = 3;  //待机模式
  }
  // [%] [0|100]
  optional double throttle_pedal_actual = 1;    //底盘反馈的实际油门大小
  // Drive system communication fault [] [0|1]
  optional Throttle_flt2Type throttle_flt2 = 2;
  // Drive system hardware fault [] [0|1]
  optional Throttle_flt1Type throttle_flt1 = 3;
  // [] [0|2]
  optional Throttle_en_stateType throttle_en_state = 4;
}

message Brake_report_501 {   //制动反馈控制信息的结构体
// Report Message
  enum Brake_flt2Type {                             //制动系统通信的超时枚举
    BRAKE_FLT2_NO_FAULT = 0;                        //无故障
    BRAKE_FLT2_BRAKE_SYSTEM_COMUNICATION_FAULT = 1; //制动系统通信超时故障
  }
  enum Brake_flt1Type {                           //制动系统硬件故障枚举      
    BRAKE_FLT1_NO_FAULT = 0;                      //无故障
    BRAKE_FLT1_BRAKE_SYSTEM_HARDWARE_FAULT = 1;   //制动系统通信超时故障
  }
  enum Brake_en_stateType {     //制动系统的模式枚举
    BRAKE_EN_STATE_MANUAL = 0;  //手动模式
    BRAKE_EN_STATE_AUTO = 1;    //自动模式
    BRAKE_EN_STATE_TAKEOVER = 2;//接管模式
    BRAKE_EN_STATE_STANDBY = 3; //待机模式
  }
  // [%] [0|100]
  optional double brake_pedal_actual = 1;      //实际的制动压力
  // Brake system communication fault [] [0|1]
  optional Brake_flt2Type brake_flt2 = 2; 
  // Brake system hardware fault [] [0|1]
  optional Brake_flt1Type brake_flt1 = 3;
  // [] [0|2]
  optional Brake_en_stateType brake_en_state = 4;
}

message Steering_report_502 {  //转向反馈信息的结构
// Report Message
  enum Steer_flt2Type {                            //转向通信的超时故障
    STEER_FLT2_NO_FAULT = 0;                       //无故障
    STEER_FLT2_STEER_SYSTEM_COMUNICATION_FAULT = 1;//转向通信的超时故障
  }
  enum Steer_flt1Type {                            //EPS模块的硬件故障
    STEER_FLT1_NO_FAULT = 0;                       //无故障
    STEER_FLT1_STEER_SYSTEM_HARDWARE_FAULT = 1;    //有故障
  }
  enum Steer_en_stateType {                        //EPS的模式枚举
    STEER_EN_STATE_MANUAL = 0;
    STEER_EN_STATE_AUTO = 1;
    STEER_EN_STATE_TAKEOVER = 2;
    STEER_EN_STATE_STANDBY = 3;
  }
  // [deg/s] [0|0]
  optional int32 steer_angle_spd_actual = 1;      //实际的转向速度
  // Steer system communication fault [] [0|255]
  optional Steer_flt2Type steer_flt2 = 2;         //通信延时故障码
  // Steer system hardware fault [] [0|255]
  optional Steer_flt1Type steer_flt1 = 3;         //硬件故障码
  // [] [0|2]
  optional Steer_en_stateType steer_en_state = 4; //EPS的模式
  // [deg] [-500|500]
  optional int32 steer_angle_actual = 5;          //EPS的实际转向角度
  // [deg] [-500|500]
  optional int32 steer_angle_rear_actual = 6;     //后轮实际角度 [也不懂,难道是后轮也能转向的车]
}

message Gear_report_503 {    //档位的反馈信息结构体
// Report Message
  enum Gear_fltType {       //档位的故障
    GEAR_FLT_NO_FAULT = 0;  //无故障
    GEAR_FLT_FAULT = 1;     //有故障
  }
  enum Gear_actualType {    //档位的反馈状态
    GEAR_ACTUAL_INVALID = 0;//档位无效
    GEAR_ACTUAL_PARK = 1;   //驻车P档
    GEAR_ACTUAL_REVERSE = 2;//倒车档R档
    GEAR_ACTUAL_NEUTRAL = 3;//空档N档
    GEAR_ACTUAL_DRIVE = 4;  //前进挡D档
  }
  // [] [0|1]
  optional Gear_fltType gear_flt = 1;
  // [] [0|4]
  optional Gear_actualType gear_actual = 2; //实际的档位
}

message Park_report_504 {   //EPB驻车反馈信息结构体
// Report Message
  enum Parking_actualType {            //实际的驻车状态
    PARKING_ACTUAL_RELEASE = 0;        //驻车释放
    PARKING_ACTUAL_PARKING_TRIGGER = 1;//驻车拉起
  }
  enum Park_fltType {      //驻车故障
    PARK_FLT_NO_FAULT = 0; //无故障
    PARK_FLT_FAULT = 1;    //有故障
  }
  // [] [0|1]
  optional Parking_actualType parking_actual = 1; //实际的驻车状态
  // [] [0|1]
  optional Park_fltType park_flt = 2;
}

message Vcu_report_505 { //Vehicle Control Unit整车控制器的反馈信息的结构体
// Report Message
  enum Vehicle_mode_stateType {                //车辆的模式
    VEHICLE_MODE_STATE_MANUAL_REMOTE_MODE = 0; //远程驾驶模式
    VEHICLE_MODE_STATE_AUTO_MODE = 1;          //自动模式
    VEHICLE_MODE_STATE_EMERGENCY_MODE = 2;     //紧急模式
    VEHICLE_MODE_STATE_STANDBY_MODE = 3;       //标准模式
  }
  enum Aeb_modeType {
    AEB_MODE_DISABLE = 0;
    AEB_MODE_ENABLE = 1;
  }
  enum Brake_light_actualType {
    BRAKE_LIGHT_ACTUAL_BRAKELIGHT_OFF = 0;
    BRAKE_LIGHT_ACTUAL_BRAKELIGHT_ON = 1;
  }
  enum Turn_light_actualType {
    TURN_LIGHT_ACTUAL_TURNLAMPSTS_OFF = 0;
    TURN_LIGHT_ACTUAL_LEFT_TURNLAMPSTS_ON = 1;
    TURN_LIGHT_ACTUAL_RIGHT_TURNLAMPSTS_ON = 2;
    TURN_LIGHT_ACTUAL_HAZARD_WARNING_LAMPSTS_ON = 3;
  }
  enum Drive_mode_stsType {
    DRIVE_MODE_STS_THROTTLE_PADDLE_DRIVE_MODE = 0;
    DRIVE_MODE_STS_SPEED_DRIVE_MODE = 1;
  }
  enum Steer_mode_stsType {
    STEER_MODE_STS_STANDARD_STEER_MODE = 0;
    STEER_MODE_STS_NON_DIRECTION_STEER_MODE = 1;
    STEER_MODE_STS_SYNC_DIRECTION_STEER_MODE = 2;
  }
  enum Frontcrash_stateType {
    FRONTCRASH_STATE_NO_EVENT = 0;
    FRONTCRASH_STATE_CRASH_EVENT = 1;
  }
  enum Backcrash_stateType {
    BACKCRASH_STATE_NO_EVENT = 0;
    BACKCRASH_STATE_CRASH_EVENT = 1;
  }
  enum Aeb_brake_stateType {
    AEB_BRAKE_STATE_INACTIVE = 0;
    AEB_BRAKE_STATE_ACTIVE = 1;
  }
  // [] [0|0]
  optional Vehicle_mode_stateType vehicle_mode_state = 1;
  // describle the vehicle AEB mode whether was set [] [0|1]
  optional Aeb_modeType aeb_mode = 2;
  // [] [0|1]
  optional Brake_light_actualType brake_light_actual = 3;
  // [] [0|0]
  optional Turn_light_actualType turn_light_actual = 4;
  // [] [0|255]
  optional int32 chassis_errcode = 5;
  // [] [0|7]
  optional Drive_mode_stsType drive_mode_sts = 6;
  // [] [0|7]
  optional Steer_mode_stsType steer_mode_sts = 7;
  // [] [0|0]
  optional Frontcrash_stateType frontcrash_state = 8;
  // [] [0|0]
  optional Backcrash_stateType backcrash_state = 9;
  // describe the vehicle e-brake command whether was triggered by AEB [] [0|0]
  optional Aeb_brake_stateType aeb_brake_state = 10;
  // [m/s^2] [-10|10]
  optional double acc = 11;
  // [m/s] [-32.768|32.767]
  optional double speed = 12;
}

message Wheelspeed_report_506 { //轮速反馈的结构体,can报文的id为506
// Report Message
  // [m/s] [0|65.535]
  optional double rr = 1;      //后右轮速
  // [m/s] [0|65.535]
  optional double rl = 2;      //后左轮速
  // [m/s] [0|65.535]
  optional double fr = 3;      //前右轮速
  // [m/s] [0|65.535]
  optional double fl = 4;      //前左轮速
}

//********【end】 这一部分反馈信息,也就是底盘的ecu的状态通过vcu反馈给ipc*************//

message Ultr_sensor_1_507 {                //超声波的数据结构,can报文的id为507
// Report Message
  // [cm] [0|65535]
  optional double uiuss9_tof_direct = 1;   //第9个超声波的探测距离
  // [cm] [0|65535]
  optional double uiuss8_tof_direct = 2;   //第8个超声波的探测距离
  // [cm] [0|65535]
  optional double uiuss11_tof_direct = 3;  //第11个超声波的探测距离
  // [cm] [0|65535]
  optional double uiuss10_tof_direct = 4;  //第10个超声波的探测距离
}

message Ultr_sensor_2_508 {
// Report Message
  // [cm] [0|65535]
  optional double uiuss9_tof_indirect = 1;
  // [cm] [0|65535]
  optional double uiuss8_tof_indirect = 2;
  // [cm] [0|65535]
  optional double uiuss11_tof_indirect = 3;
  // [cm] [0|65535]
  optional double uiuss10_tof_indirect = 4;
}

message Ultr_sensor_3_509 {
// Report Message
  // [cm] [0|65535]
  optional double uiuss5_tof_direct = 1;
  // [cm] [0|65535]
  optional double uiuss4_tof_direct = 2;
  // [cm] [0|65535]
  optional double uiuss3_tof_direct = 3;
  // [cm] [0|65535]
  optional double uiuss2_tof_direct = 4;
}

message Ultr_sensor_4_510 {
// Report Message
  // [cm] [0|65535]
  optional double uiuss5_tof_indirect = 1;
  // [cm] [0|65535]
  optional double uiuss4_tof_indirect = 2;
  // [cm] [0|65535]
  optional double uiuss3_tof_indirect = 3;
  // [cm] [0|65535]
  optional double uiuss2_tof_indirect = 4;
}

message Ultr_sensor_5_511 {
// Report Message
  // [cm] [0|65535]
  optional double uiuss7_tof_direct = 1;
  // [cm] [0|65535]
  optional double uiuss6_tof_direct = 2;
  // [cm] [0|65535]
  optional double uiuss1_tof_direct = 3;
  // [cm] [0|65535]
  optional double uiuss0_tof_direct = 4;
}

message Bms_report_512 {                     //BMS电源模块
// Report Message
  enum Battery_flt_lowtempType {             // 电源低温故障
    BATTERY_FLT_LOW_TEMP_NO_FAULT  = 0;
    BATTERY_FLT_LOW_TEMP_FAULT = 1;
  }
  enum Battery_flt_overtempType {            //电源超温故障
    BATTERY_FLT_OVER_TEMP_NO_FAULT  = 0;
    BATTERY_FLT_OVER_TEMP_FAULT = 1;
  }
  // Battery Total Current [A] [-3200|3200]
  optional double battery_current = 1;        //电源模块的电流 
  // Battery Total Voltage [V] [0|300]
  optional double battery_voltage = 2;        //电池当前电压
  // Battery State of Charge percentage [%] [0|100]
  optional int32 battery_soc_percentage = 3;  //当前的电量百分比
  // Battery Low Soc Warn
  optional bool is_battery_soc_low = 4;      //是否处于低电量模式
  // Battery inside temperature
  optional double battery_inside_temperature = 5;//电池内部温度
  // Battery Below Low temp fault
  optional Battery_flt_lowtempType battery_flt_low_temp = 6;
  // Battery Over High Temp fault
  optional Battery_flt_overtempType battery_flt_over_temp = 7;
}

message Vin_resp1_514 {   //车辆的vin码
// Report Message
  // [] [0|255] to char
  optional string vin07 = 1;
  // [] [0|255] to char
  optional string vin06 = 2;
  // [] [0|255] to char
  optional string vin05 = 3;
  // [] [0|255] to char
  optional string vin04 = 4;
  // [] [0|255] to char
  optional string vin03 = 5;
  // [] [0|255] to char
  optional string vin02 = 6;
  // [] [0|255] to char
  optional string vin01 = 7;
  // [] [0|255] to char
  optional string vin00 = 8;
}

message Vin_resp2_515 {  //车辆的win码
// Report Message
  // [] [0|255] to char
  optional string vin15 = 1;
  // [] [0|255] to char
  optional string vin14 = 2;
  // [] [0|255] to char
  optional string vin13 = 3;
  // [] [0|255] to char
  optional string vin12 = 4;
  // [] [0|255] to char
  optional string vin11 = 5;
  // [] [0|255] to char
  optional string vin10 = 6;
  // [] [0|255] to char
  optional string vin09 = 7;
  // [] [0|255] to char
  optional string vin08 = 8;
}

message Vin_resp3_516 {  //车辆vin码
// Report Message
  // [] [0|255] to char
  optional string vin16 = 1;
}

// CheckResponseSignal
message CheckResponseSignal {
  optional bool is_eps_online = 1 [default = false];    //EPS电子助力转向系统是否在线
  optional bool is_epb_online = 2 [default = false];    //EPB电子驻车制动系统是否在线
  optional bool is_esp_online = 3 [default = false];    //ESP电子稳定控制系统是否在线
  optional bool is_vtog_online = 4 [default = false];   
  optional bool is_scu_online = 5 [default = false];
  optional bool is_switch_online = 6 [default = false];
  optional bool is_vcu_online = 7 [default = false];    //VCU车辆控制单元是否在线
}

message Devkit {
  optional Throttle_command_100 throttle_command_100 = 1; // control message
  optional Brake_command_101 brake_command_101 = 2; // control message
  optional Steering_command_102 steering_command_102 = 3; // control message
  optional Gear_command_103 gear_command_103 = 4; // control message
  optional Park_command_104 park_command_104 = 5; // control message
  optional Throttle_report_500 throttle_report_500 = 6; // report message
  optional Brake_report_501 brake_report_501 = 7; // report message
  optional Steering_report_502 steering_report_502 = 8; // report message
  optional Gear_report_503 gear_report_503 = 9; // report message
  optional Park_report_504 park_report_504 = 10; // report message
  optional Vcu_report_505 vcu_report_505 = 11; // report message
  optional Wheelspeed_report_506 wheelspeed_report_506 = 12; // report message
  optional Ultr_sensor_1_507 ultr_sensor_1_507 = 13; // report message
  optional Ultr_sensor_2_508 ultr_sensor_2_508 = 14; // report message
  optional Ultr_sensor_3_509 ultr_sensor_3_509 = 15; // report message
  optional Ultr_sensor_4_510 ultr_sensor_4_510 = 16; // report message
  optional Ultr_sensor_5_511 ultr_sensor_5_511 = 17; // report message
  optional Bms_report_512 bms_report_512 = 18; // report message
  optional Vehicle_mode_command_105 vehicle_mode_command_105 = 19; // control message
  optional Vin_resp1_514 vin_resp1_514 = 20; // report message
  optional Vin_resp2_515 vin_resp2_515 = 21; // report message
  optional Vin_resp3_516 vin_resp3_516 = 22; // report message

  optional CheckResponseSignal check_response = 100;
}