source: pacpussensors/trunk/CanGateway/driver/KVaserCanDriver.cpp@ 122

Last change on this file since 122 was 116, checked in by ydroniou, 9 years ago

Fix KVaser for Linux \o/

File size: 7.0 KB
RevLine 
[89]1/// @date created 2015/06/23
2/// @author Gerald Dherbomez
3/// @version $Id$
4
5#include "KVaserCanDriver.h"
[116]6/*
[94]7#ifdef WIN32
8#include "kvaser/windows/canlib.h"
9#else
10#include "kvaser/linux/canlib.h"
11#endif
[116]12*/
13
14
15#include <canlib.h>
16
[89]17#include <cassert>
18#include <cstdio>
19#include <iomanip>
20#include <iostream>
21#include <string>
[94]22#include <string.h>
[89]23
24#include "Pacpus/kernel/Log.h"
25#include "../CanFrame.h"
26
27using namespace pacpus;
28using namespace std;
29
30DECLARE_STATIC_LOGGER("pacpussensors.CanGateway.KVaserCanDriver");
31
32#define WAIT_RECEIVING_FRAME_TIMEOUT 1000
33
34/*
35#define RX_QUEUE_SIZE 4096
36#define QUEUE_LEVEL 1
37
38bool checkXlStatus(const XLstatus status) {
39 if ( status != XL_SUCCESS ) {
40 XLstringType error = xlGetErrorString(status);
41 LOG_ERROR(error);
42 return false;
43 } else {
44 return true;
45 }
46
47}
48*/
49//
50// Check a status code and issue an error message if the code isn't canOK.
51//
[116]52void ErrorExit(string id, canStatus stat)
[89]53{
54 char buf[50];
55 if (stat != canOK) {
56 buf[0] = '\0';
57 canGetErrorText(stat, buf, sizeof(buf));
[94]58 LOG_ERROR(id << ": failed, stat=" << (int)stat << " (" << buf << ")");
[89]59 //exit(1);
60 }
61}
62
63/**
64* Constructor which enables to initialize the different attributes of the class with default values.
65* @see ~KVaserCanDriver (void)
66*/
67
68KVaserCanDriver::KVaserCanDriver(int channel, unsigned int bitRate)
69{
70 LOG_INFO("Notice : KVASER CAN Driver used\n");
71 canChannel_ = channel;
72 canBitRate_ = bitRate;
73 kvaserHardwareType_ = 0;
74}
75
76
77/**
78* Constructor which enables to initialize the different attributes of the class with default values.
79* @see ~KVaserCanDriver (void)
80* @see KVaserCanDriver (unsigned int gHwTypeT, Vaccess gChannelMaskT, unsigned int gCanIdT, unsigned int gBitRateT,int gHwChannelT)
81*/
82
83KVaserCanDriver::KVaserCanDriver (void)
84{
85 LOG_INFO("Notice : KVASER CAN Driver used\n");
86 canChannel_ = 0;
87 canBitRate_ = 500000;
88 kvaserHardwareType_ = 0;
89}
90
91/**
92* Constructor which enables to initialize the different attributes of the class with values given in parameters.
93* @see ~KVaserCanDriver (void)
94* @see KVaserCanDriver (void)
95*/
96KVaserCanDriver::KVaserCanDriver(const int hwType, const int hwChannel, const unsigned long bitrate)
97{
98 canChannel_ = hwChannel;
99 canBitRate_ = bitrate;
100 kvaserHardwareType_ = hwType;
101}
102
103
104/**
105* Constructor which enables to select the channel and to initialize the different attributes of the class with default values..
106* @see ~KVaserCanDriver (void)
107* @see KVaserCanDriver (void)
108*/
109
110KVaserCanDriver::KVaserCanDriver(int channel)
111{
112 LOG_INFO("Notice : KVASER CAN Driver used\n");
113 canChannel_ = channel;
114 canBitRate_ = 500000;
115 kvaserHardwareType_ = 0;
116}
117
118
119
120/**
121* Destructor which clean up the different attributs of the class.
122* @see KVaserCanDriver (void)
123*/
124KVaserCanDriver::~KVaserCanDriver (void)
125{
126
127}
128
129
130
[116]131void KVaserCanDriver::displayHardware()
[89]132{
133 LOG_INFO("----------------------------------------------------------");
134 LOG_INFO("KVASER DRIVER HARDWARE INFORMATION -- TODO");
135 LOG_INFO("KVASER DRIVER VERSION: 5_11_931 ");
136 LOG_INFO("----------------------------------------------------------");
137}
138
139
140void KVaserCanDriver::initialize(const int hwType, const int hwChannel, const unsigned long bitrate)
141{
142 LOG_INFO("Notice : KVASER CAN Driver used\n");
143 displayHardware();
144
145 canHandle_ = canOpenChannel(hwChannel, 0);
146 if (canHandle_ < 0) {
[116]147 ErrorExit("canOpenChannel", (canStatus) canHandle_);
[89]148 }
[116]149 else
[89]150 {
151 int ret = 0;
152 switch (bitrate)
153 {
154 case 125000:
155 ret = canSetBusParams(canHandle_, canBITRATE_125K, 0, 0, 0, 0, 0);
156 break;
157 case 250000:
158 ret = canSetBusParams(canHandle_, canBITRATE_250K, 0, 0, 0, 0, 0);
159 break;
160 case 500000:
[116]161 ret = canSetBusParams(canHandle_, canBITRATE_500K, 4, 3, 1, 1, 0);
[89]162 break;
163 default:
164 ret = canERR_NOTFOUND;
165 break;
166 }
167 if (ret < 0) {
168 ErrorExit("canSetBusParams", (canStatus)ret);
169 }
170
171 ret = canBusOn(canHandle_);
172 if (ret < 0) {
173 ErrorExit("canBusOn", (canStatus)ret);
[116]174
[89]175 }
176 }
177}
178
179
180/**
181* Member used to initialise the configuration of the CAN Card.
182* @see cleanUpPort (void)
183* @return a Vstatus variable which contain the error code of the function. On success, it return VSUCCESS. On failure, it return Vstatus error code which is defined in VCanD.h
184*/
185short KVaserCanDriver::initPort (void)
186{
[94]187#ifdef WIN32
[89]188 // Initialize CANLIB.
189 //
190 canInitializeLibrary();
[94]191#endif
[116]192
[89]193 // open the physical CAN interface
194 initialize(kvaserHardwareType_, canChannel_, canBitRate_);
195
196 return 0;
197}
198
199
200/**
201* Member used to clean up the configuration of the CAN Card.
202* @see initPort (void)
203* @return a Vstatus variable which contain the error code of the function. On success, it return VSUCCESS. On failure, it return Vstatus error code which is defined in VCanD.h
204*/
205short KVaserCanDriver::cleanUpPort (void)
206{
[116]207
[89]208 //traceXLCommand("xlCloseDriver", xlCloseDriver());
209
210 canBusOff(canHandle_);
211 canClose(canHandle_);
212
213 return 0;
214}
215
216
217/**
218* Member which permit to send a frame on the CAN bus and test if the frame is well acknowledged.
219*/
220short KVaserCanDriver::sendFrame (struct CanFrame frame)
221{
222 canStatus stat = canWrite(canHandle_, frame.id,frame.data, frame.dlc, 0);
[116]223 if (stat == canOK )
[89]224 {
225 return 0;
226 } else {
227 LOG_WARN("Kvaser driver - sendFrame method - Failed to send the CAN frame");
[116]228 return 1;
[89]229 }
230}
231
232
233/**
234* Member which permit to receive of a frame on the CAN bus.
235*/
236//Vstatus KVaserCanDriver::receiveFrame (unsigned char * flags, unsigned char * dlc, unsigned char * data, int * identifiant)
237short KVaserCanDriver::receiveFrame (struct CanFrame &frame)
238{
239 long id;
240 unsigned int dlc, flags;
241 unsigned char msg[8];
[94]242 //DWORD timestamp;
243 unsigned long timestamp;
[116]244
[94]245 canStatus stat = canReadWait(canHandle_, &id, msg, &dlc, &flags, &timestamp, WAIT_RECEIVING_FRAME_TIMEOUT);
[116]246 if (stat == canOK )
[89]247 {
[116]248 if ((flags & canMSG_ERROR_FRAME) == 0)
[89]249 {
250 // Get the message data
251 /*fprintf(f, "%8lu%c%c%c%c %02lu ",
252 id,
253 flags & canMSG_EXT ? 'x' : ' ',
254 flags & canMSG_RTR ? 'R' : ' ',
255 flags & canMSGERR_OVERRUN ? 'o' : ' ',
256 flags & canMSG_NERR ? 'N' : ' ', // TJA 1053/1054 transceivers only
257 dlc);*/
258 frame.id = id;
259 frame.dlc = dlc;
260 memcpy(frame.data, msg, frame.dlc);
261 return 0;
[116]262 }
263 }
[91]264 else if (stat == canERR_NOMSG ) {
[89]265 // timeout occurs
266 LOG_WARN("Kvaser card - receiveFrame() method - TIMEOUT");
267 return 1;
[116]268 }
[91]269 else {
[89]270 // An error frame.
271 LOG_WARN("Kvaser card, error frame");
272 return 1;
273 }
274
[91]275
276 return 1;
[89]277}
278
279
280/**
281* Member which wait the reception of a frame on the CAN bus.
282* @see sendFrame (unsigned char flags, unsigned char dlc, unsigned char * data)
283* @see receiveFrame (unsigned char * flags, unsigned char * dlc, unsigned char ** data)
284*/
285void KVaserCanDriver::waitReceivingFrame(void)
286{
287 LOG_WARN("KVASER driver - waitReceivingFrame(void) method - Not yet implemented");
288}
Note: See TracBrowser for help on using the repository browser.