目录
基本概念
CAN Card
CAN - 原始套接字
ESD CAN 监控分析
Socket Can监控分析
基本概念
CAN Card
首先需要直到CAN的一些基本的概念。
CAN 是Controller Area Network 的缩写(以下称为CAN),是ISO国际标准化的串行通信协议。在汽车产业中,出于对安全性、舒适性、方便性、低功耗、低成本的要求,各种各样的电子控制系统被开发了出来。
CAN卡的CAN总线数据收发由CAN控制器和CAN收发器完成.这种接口的卡在汽车行业中应用广泛,而且在工业控制、机器人、医疗器械、传感器等领域发展迅速。
目前apollo都使用的德国esd的can卡 ESD CAN-PCIe/402-1,apollo1.0-1.5使用的此款can卡。
can卡会有自己的驱动,一般由设备厂商提供,所以这里的CAN监控,其中一个监控就是看这个can的驱动是不是可以输出正确的信号。
CAN - 原始套接字
我们的业务软件想要了解车端的设备状态就需要从can 上读取状态,这里主要使用的就是socket can,Socket CAN采用的即是原始套接字。该接口允许对较底层协议进行操作,如IP、ICMP等。原始套接字常用于检验新的协议实现或访问现有服务中配置的新设备。
套接字的工作流程如下:
先启动服务器,通过调用socket()函数建立一个套接字,然后调用bind()函数将该套接字和本地网络地址联系在一起,再调用listen()函数使套接字做好侦听的准备,并规定它的请求队列的长度,之后就调用accept()函数来接收连接。客户端在建立套接字之后就可调用 connect()和服务器建立连接。连接一旦建立,客户端和服务器之间就可以通过调用recv()/recvfrom()函数和send()/sendto函数来进行发收数据。最后,待数据传送结束后,双方调用close()函数关闭套接字。
参考Link:Linux SocketCAN 编程(C++,启用多线程接收)_地球被支点撬走啦的博客-CSDN博客_linux socketcan
所以apollo 的can 监控中另外一个监控就是针对链路的- can的socket 通信链路。
ESD CAN 监控分析
class EsdCanMonitor : public RecurrentRunner {
public:
EsdCanMonitor();
void RunOnce(const double current_time) override;
};
void EsdCanMonitor::RunOnce(const double current_time) {
Component* component = apollo::common::util::FindOrNull(
*MonitorManager::Instance()->GetStatus()->mutable_components(),
FLAGS_esdcan_component_name);
if (component == nullptr) {
// Canbus is not monitored in current mode, skip.
return;
}
auto* status = component->mutable_other_status();
status->clear_status();
EsdCanTest(FLAGS_esdcan_id, status);
}
可以看到首先还是判断配置文件是否配置了这个内容,如果没有配置这个监控直接return。
然后就使用EsdCanTest 这个函数检查Can card 的状态,所以核心就在EsdCanTest。
NTCAN_RESULT EsdCanTest(const int can_id, NTCAN_HANDLE* handle) {
NTCAN_RESULT ret = canOpen(can_id, 0, 1, 1, 0, 0, handle);
if (ret == NTCAN_SUCCESS) {
AINFO << "Successfully opened ESD-CAN device " << can_id;
} else {
AERROR << "Failed to open ESD-CAN device " << can_id << ", error: " << ret
<< " (" << StatusString(ret) << ")";
return ret;
}
CAN_IF_STATUS if_status;
ret = canStatus(*handle, &if_status);
if (ret != NTCAN_SUCCESS) {
AERROR << "Cannot get status of ESD-CAN, ret=" << ret << " ("
<< StatusString(ret) << ")";
return ret;
}
NTCAN_BUS_STATISTIC stats;
ret = canIoctl(*handle, NTCAN_IOCTL_GET_BUS_STATISTIC, &stats);
if (ret != NTCAN_SUCCESS) {
AERROR << "NTCAN_IOCTL_GET_BUS_STATISTIC failed for device with error: "
<< ret << " (" << StatusString(ret) << ")";
return ret;
}
NTCAN_CTRL_STATE ctrl_state;
ret = canIoctl(*handle, NTCAN_IOCTL_GET_CTRL_STATUS, &ctrl_state);
if (ret != NTCAN_SUCCESS) {
AERROR << "NTCAN_IOCTL_GET_CTRL_STATUS failed for device with error: "
<< ret << " (" << StatusString(ret) << ")";
return ret;
}
NTCAN_BITRATE bitrate;
ret = canIoctl(*handle, NTCAN_IOCTL_GET_BITRATE_DETAILS, &bitrate);
if (ret != NTCAN_SUCCESS) {
AERROR << "NTCAN_IOCTL_GET_BITRATE_ for device with error: " << ret << " ("
<< StatusString(ret) << ")";
return ret;
}
return ret;
}
void EsdCanTest(const int can_id, ComponentStatus* status) {
NTCAN_HANDLE handle;
const NTCAN_RESULT ret = EsdCanTest(can_id, &handle);
canClose(handle);
SummaryMonitor::EscalateStatus(
ret == NTCAN_SUCCESS ? ComponentStatus::OK : ComponentStatus::ERROR,
StatusString(ret), status);
}
#else
// USE_ESD_CAN is not set, do dummy check.
void EsdCanTest(const int can_id, ComponentStatus* status) {
SummaryMonitor::EscalateStatus(ComponentStatus::ERROR,
"USE_ESD_CAN is not defined during compiling",
status);
}
#endif
这里可以看出,如果发现没有安装CAN 卡的话会直接报错,如果安装了,会调用,canopen打开一个can设备,然后使用canstatus、canIoctl去判断can设备现在的状态,并最终把状态ret进行返回。
如果ret 不为NTCAN_SUCCESS ,就报ERROR,反之就报OK。
Socket Can监控分析
class SocketCanMonitor : public RecurrentRunner {
public:
SocketCanMonitor();
void RunOnce(const double current_time) override;
};
void SocketCanMonitor::RunOnce(const double current_time) {
auto manager = MonitorManager::Instance();
Component* component = apollo::common::util::FindOrNull(
*manager->GetStatus()->mutable_components(),
FLAGS_socket_can_component_name);
if (component == nullptr) {
// Canbus is not monitored in current mode, skip.
return;
}
auto* status = component->mutable_other_status();
status->clear_status();
std::string message;
const bool ret = SocketCanTest(&message);
SummaryMonitor::EscalateStatus(
ret ? ComponentStatus::OK : ComponentStatus::ERROR, message, status);
}
一样的套路,第一步检查socket can是不是被配置为监控对象,如果是的话就调用SocketCanTest,对socket can进行检查,并返回ret。
若ret为false就报ERROR故障,反之就报OK的状态。
bool SocketCanTest(std::string* message) {
const int dev_handler = socket(PF_CAN, SOCK_RAW, CAN_RAW);
if (dev_handler < 0) {
*message = "Open can device failed";
return false;
}
const bool ret = SocketCanHandlerTest(dev_handler, message);
close(dev_handler);
return ret;
}
- socket(PF_CAN, SOCK_RAW, CAN_RAW);就是创建一个can 原生socket
- 交给SocketCanHandlerTest做检查
// Test Socket CAN on an open handler.
bool SocketCanHandlerTest(const int dev_handler, std::string* message) {
// init config and state
// 1. set receive message_id filter, ie white list
struct can_filter filter[1];
filter[0].can_id = 0x000;
filter[0].can_mask = CAN_SFF_MASK;
int ret = setsockopt(dev_handler, SOL_CAN_RAW, CAN_RAW_FILTER, &filter,
sizeof(filter));
if (ret < 0) {
*message = "set message filter failed";
return false;
}
// 2. enable reception of can frames.
const int enable = 1;
ret = setsockopt(dev_handler, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &enable,
sizeof(enable));
if (ret < 0) {
*message = "Enable reception of can frames failed";
return false;
}
struct ifreq ifr;
std::strncpy(ifr.ifr_name, "can0", IFNAMSIZ);
if (ioctl(dev_handler, SIOCGIFINDEX, &ifr) < 0) {
*message = "ioctl failed";
return false;
}
// bind socket to network interface
struct sockaddr_can addr;
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
ret = bind(dev_handler, reinterpret_cast<struct sockaddr*>(&addr),
sizeof(addr));
if (ret < 0) {
*message = "bind socket can failed";
return false;
}
return true;
}
- 设置过滤器,这里只接收标识符等于0x00的报文,如果设置失败就返回false,并传出异常日志
- 启动can帧的接收,如果启动失败就返回false,并传出异常日志
- 映射实际的can接口,如果失败就反馈false,并传出异常日志
- 把socket绑定到网络接口如果绑定失败就返回false,并传出异常日志
- 如果上述都成功就返回true
参考link:can口通信详解_时费的博客-CSDN博客_can口