【简介】基于前ROS CAN总线设备接入(一),我们成功实现了对于libpcan库的使用,本次将实现对于can总线的初始化以及对于can总线上有效数据提取,并将其以topic形式发布到ros节点中。
【正文】
1,要完成数据读取,需要对以下函数进行映射。
- //one-to-one mapping using dlsym function,if return null,mapping would be failed
- funCAN_Init =(funCAN_Init_TYPE) dlsym(libm_handle,"CAN_Init");
- funLINUX_CAN_Open =(funLINUX_CAN_Open_TYPE) dlsym(libm_handle,"LINUX_CAN_Open");
- funCAN_Close =(funCAN_Close_TYPE) dlsym(libm_handle,"CAN_Close");
- funCAN_VersionInfo =(funCAN_VersionInfo_TYPE) dlsym(libm_handle,"CAN_VersionInfo");
- funLINUX_CAN_Read =(funLINUX_CAN_Read_TYPE) dlsym(libm_handle,"LINUX_CAN_Read");
- funCAN_Status =(funCAN_Status_TYPE) dlsym(libm_handle,"CAN_Status");
- funnGetLastError =(funnGetLastError_TYPE) dlsym(libm_handle,"nGetLastError");
映射的方法在设备接入(一)教程中有详细介绍。程序中用了多处dlerror()进行dlfcn函数调用中的错误处理,该函数每次调用会清除之前错误队列,返回当前函数调用出现的错误。
2,pcan使用时可以先打开,再进行波特率、标准模式或扩展模式的设置等操作。
- char txt[VERSIONSTRING_LEN]; //store information of can version,存储信息
- unsigned short wBTR0BTR1 = CAN_BAUD_1M; //set the communicate baud rate of can bus,波特率
- int nExtended = CAN_INIT_TYPE_ST; //set can message int standard model,标准模式
- const char *szDevNode = DEFAULT_NODE; //define const pointer point to device name,定义设备地址
- pcan_handle = funLINUX_CAN_Open(szDevNode, O_RDWR );//use mapping function
如果打开的pcan_handle非空,则函数调用成功,进行下一步处理。此处进行了打开成功的提示,并通过读取驱动can的版本号来验证是否驱动成功。
- //judge whether the call is success.if pcan_handle=null,the call would be failed
- if(pcan_handle){
- printf("CAN Bus test: %s have been opened\n", szDevNode);
- errno = funCAN_VersionInfo(pcan_handle, txt);
- if (!errno)
- printf("CAN Bus test: driver version = %s\n", txt);
- else {
- perror("CAN Bus test: CAN_VersionInfo()");
- }
以上程序片段即完成了打开can是否成功的验证,运行时会输出以下类似信息。
- robot@robot-ThinkPad-T410:~$ rosrun beginner_tutorials can_test
- CAN Bus test: /dev/pcan0 have been opened
- CAN Bus test: driver version = Release_20130814_n
- Device Info: /dev/pcan0; CAN_BAUD_1M; CAN_INIT_TYPE_ST
然后进行初始化函数的调用,wBTR0BTR1代表了can的波特率,引用此名称主要参考lipcan官方给的测试源码,这样后期其许多函数移植会比较方便。
- if (wBTR0BTR1) {
- errno = funCAN_Init(pcan_handle, wBTR0BTR1, nExtended);
- if (errno) {
- perror("CAN Bus test: CAN_Init()");
- }
- else
- printf("Device Info: %s; CAN_BAUD_1M; CAN_INIT_TYPE_ST\n", szDevNode);
- }
- }
- else
- printf("CAN Bus test: can't open %s\n", szDevNode);
3,数据的提取和发布。要实现数据的提取和发布需要以下函数进行辅助,将分别对其做介绍。
- //function declaration
- int read_loop(HANDLE h,ros::Publisher pub,bool display_on,bool publish_on);<span style="white-space:pre">//循环读取函