00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include <cob_generic_can/CanPeakSys.h>
00019 #include <stdlib.h>
00020 #include <cerrno>
00021 #include <cstring>
00022 #include <sys/types.h>
00023 #include <sys/stat.h>
00024 #include <fcntl.h>
00025 #include <unistd.h>
00026
00027
00028 const int CanPeakSys::c_iInterrupt = 7;
00029 const int CanPeakSys::c_iPort = 0x378;
00030
00031
00032 CanPeakSys::CanPeakSys(const char* cIniFile)
00033 {
00034 m_bInitialized = false;
00035
00036
00037 m_IniFile.SetFileName(cIniFile, "CanPeakSys.cpp");
00038 init();
00039 }
00040
00041
00042 CanPeakSys::~CanPeakSys()
00043 {
00044 if (m_bInitialized)
00045 {
00046 CAN_Close(m_handle);
00047 }
00048 }
00049
00050
00051 bool CanPeakSys::init_ret()
00052 {
00053
00054 return false;
00055 }
00056
00057
00058 void CanPeakSys::init()
00059 {
00060 std::string sCanDevice;
00061 if( m_IniFile.GetKeyString( "TypeCan", "DevicePath", &sCanDevice, false) != 0) {
00062 sCanDevice = "/dev/pcan32";
00063 } else std::cout << "CAN-device path read from ini-File: " << sCanDevice << std::endl;
00064 m_handle = LINUX_CAN_Open(sCanDevice.c_str(), O_RDWR);
00065
00066
00067 if (! m_handle)
00068 {
00069
00070 std::cout << "Cannot open CAN-dongle on parallel port: " << strerror(errno) << std::endl;
00071 sleep(3);
00072 exit(0);
00073 }
00074
00075
00076 int ret = CAN_ERR_OK;
00077 int iBaudrateVal = 0;
00078 m_IniFile.GetKeyInt( "CanCtrl", "BaudrateVal", &iBaudrateVal, true);
00079
00080 switch(iBaudrateVal)
00081 {
00082 case CANITFBAUD_1M:
00083 ret = CAN_Init(m_handle, CAN_BAUD_1M, CAN_INIT_TYPE_ST);
00084 break;
00085 case CANITFBAUD_500K:
00086 ret = CAN_Init(m_handle, CAN_BAUD_500K, CAN_INIT_TYPE_ST);
00087 break;
00088 case CANITFBAUD_250K:
00089 ret = CAN_Init(m_handle, CAN_BAUD_250K, CAN_INIT_TYPE_ST);
00090 break;
00091 case CANITFBAUD_125K:
00092 ret = CAN_Init(m_handle, CAN_BAUD_125K, CAN_INIT_TYPE_ST);
00093 break;
00094 case CANITFBAUD_50K:
00095 ret = CAN_Init(m_handle, CAN_BAUD_50K, CAN_INIT_TYPE_ST);
00096 break;
00097 case CANITFBAUD_20K:
00098 ret = CAN_Init(m_handle, CAN_BAUD_20K, CAN_INIT_TYPE_ST);
00099 break;
00100 case CANITFBAUD_10K:
00101 ret = CAN_Init(m_handle, CAN_BAUD_10K, CAN_INIT_TYPE_ST);
00102 break;
00103 }
00104
00105 if(ret)
00106 {
00107 std::cout << "CanPeakSys::CanPeakSys(), error in init" << std::endl;
00108 }
00109 else
00110 {
00111 std::cout << "CanPeakSys::CanpeakSys(), init ok" << std::endl;
00112 m_bInitialized = true;
00113 }
00114 }
00115
00116
00117 bool CanPeakSys::transmitMsg(CanMsg CMsg, bool bBlocking)
00118 {
00119 TPCANMsg TPCMsg;
00120 bool bRet = true;
00121
00122 if (m_bInitialized == false) return false;
00123
00124
00125 TPCMsg.LEN = CMsg.m_iLen;
00126 TPCMsg.ID = CMsg.m_iID;
00127 TPCMsg.MSGTYPE = CMsg.m_iType;
00128 for(int i=0; i<8; i++)
00129 TPCMsg.DATA[i] = CMsg.getAt(i);
00130
00131
00132 int iRet;
00133 iRet = CAN_Write(m_handle, &TPCMsg);
00134 iRet = CAN_Status(m_handle);
00135
00136 if(iRet < 0)
00137 {
00138 std::cout << "CanPeakSys::transmitMsg, errorcode= " << nGetLastError() << std::endl;
00139 bRet = false;
00140 }
00141
00142
00143 return bRet;
00144 }
00145
00146
00147 bool CanPeakSys::receiveMsg(CanMsg* pCMsg)
00148 {
00149 TPCANRdMsg TPCMsg;
00150 TPCMsg.Msg.LEN = 8;
00151 TPCMsg.Msg.MSGTYPE = 0;
00152 TPCMsg.Msg.ID = 0;
00153
00154 int iRet = CAN_ERR_OK;
00155 bool bRet = false;
00156
00157
00158 if (m_bInitialized == false) return false;
00159
00160 iRet = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, 0);
00161
00162 if (iRet == CAN_ERR_OK)
00163 {
00164 pCMsg->m_iID = TPCMsg.Msg.ID;
00165 pCMsg->set(TPCMsg.Msg.DATA[0], TPCMsg.Msg.DATA[1], TPCMsg.Msg.DATA[2], TPCMsg.Msg.DATA[3],
00166 TPCMsg.Msg.DATA[4], TPCMsg.Msg.DATA[5], TPCMsg.Msg.DATA[6], TPCMsg.Msg.DATA[7]);
00167 bRet = true;
00168 }
00169 else if (CAN_Status(m_handle) != CAN_ERR_QRCVEMPTY)
00170 {
00171 std::cout << "CanPeakSys::receiveMsg ERROR: iRet = " << iRet << std::endl;
00172 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0);
00173 }
00174 else
00175 {
00176
00177 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0);
00178 }
00179
00180 return bRet;
00181 }
00182
00183
00184 bool CanPeakSys::receiveMsgRetry(CanMsg* pCMsg, int iNrOfRetry)
00185 {
00186 int i, iRet;
00187
00188 TPCANRdMsg TPCMsg;
00189 TPCMsg.Msg.LEN = 8;
00190 TPCMsg.Msg.MSGTYPE = 0;
00191 TPCMsg.Msg.ID = 0;
00192
00193 if (m_bInitialized == false) return false;
00194
00195
00196 bool bRet = true;
00197 iRet = CAN_ERR_OK;
00198 i=0;
00199 do
00200 {
00201 iRet = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, 0);
00202
00203 if(iRet == CAN_ERR_OK)
00204 break;
00205
00206 i++;
00207 usleep(100000);
00208 }
00209 while(i < iNrOfRetry);
00210
00211
00212 if(iRet != CAN_ERR_OK)
00213 {
00214 std::cout << "CanPeakSys::receiveMsgRetry: " << strerror(errno) << std::endl;
00215 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0);
00216 bRet = false;
00217 }
00218 else
00219 {
00220 pCMsg->m_iID = TPCMsg.Msg.ID;
00221 pCMsg->set(TPCMsg.Msg.DATA[0], TPCMsg.Msg.DATA[1], TPCMsg.Msg.DATA[2], TPCMsg.Msg.DATA[3],
00222 TPCMsg.Msg.DATA[4], TPCMsg.Msg.DATA[5], TPCMsg.Msg.DATA[6], TPCMsg.Msg.DATA[7]);
00223 }
00224
00225 return bRet;
00226 }
00227
00228
00229 bool CanPeakSys::receiveMsgTimeout(CanMsg* pCMsg, int nMicroSecTimeout)
00230 {
00231 int iRet = CAN_ERR_OK;
00232
00233 TPCANRdMsg TPCMsg;
00234 TPCMsg.Msg.LEN = 8;
00235 TPCMsg.Msg.MSGTYPE = 0;
00236 TPCMsg.Msg.ID = 0;
00237
00238 if (m_bInitialized == false) return false;
00239
00240 bool bRet = true;
00241
00242 iRet = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, nMicroSecTimeout);
00243
00244
00245 if(iRet != CAN_ERR_OK)
00246 {
00247 std::cout << "CANPeakSysUSB::receiveMsgRetry, errorcode= " << nGetLastError() << std::endl;
00248 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0);
00249 bRet = false;
00250 }
00251 else
00252 {
00253 pCMsg->setID(TPCMsg.Msg.ID);
00254 pCMsg->setLength(TPCMsg.Msg.LEN);
00255 pCMsg->set(TPCMsg.Msg.DATA[0], TPCMsg.Msg.DATA[1], TPCMsg.Msg.DATA[2], TPCMsg.Msg.DATA[3],
00256 TPCMsg.Msg.DATA[4], TPCMsg.Msg.DATA[5], TPCMsg.Msg.DATA[6], TPCMsg.Msg.DATA[7]);
00257 }
00258
00259 return bRet;
00260 }