$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob3_common 00012 * ROS package name: generic_can 00013 * Description: 00014 * 00015 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00016 * 00017 * Author: Christian Connette, email:christian.connette@ipa.fhg.de 00018 * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de 00019 * 00020 * Date of creation: Feb 2009 00021 * ToDo: Remove dependency to inifiles_old -> Inifile.h 00022 * 00023 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00024 * 00025 * Redistribution and use in source and binary forms, with or without 00026 * modification, are permitted provided that the following conditions are met: 00027 * 00028 * * Redistributions of source code must retain the above copyright 00029 * notice, this list of conditions and the following disclaimer. 00030 * * Redistributions in binary form must reproduce the above copyright 00031 * notice, this list of conditions and the following disclaimer in the 00032 * documentation and/or other materials provided with the distribution. 00033 * * Neither the name of the Fraunhofer Institute for Manufacturing 00034 * Engineering and Automation (IPA) nor the names of its 00035 * contributors may be used to endorse or promote products derived from 00036 * this software without specific prior written permission. 00037 * 00038 * This program is free software: you can redistribute it and/or modify 00039 * it under the terms of the GNU Lesser General Public License LGPL as 00040 * published by the Free Software Foundation, either version 3 of the 00041 * License, or (at your option) any later version. 00042 * 00043 * This program is distributed in the hope that it will be useful, 00044 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00045 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00046 * GNU Lesser General Public License LGPL for more details. 00047 * 00048 * You should have received a copy of the GNU Lesser General Public 00049 * License LGPL along with this program. 00050 * If not, see <http://www.gnu.org/licenses/>. 00051 * 00052 ****************************************************************/ 00053 00054 //#define __DEBUG__ 00055 00056 #include <cob_generic_can/CanPeakSysUSB.h> 00057 #include <stdlib.h> 00058 #include <cerrno> 00059 #include <cstring> 00060 #include <stdlib.h> 00061 #include <sys/types.h> 00062 #include <sys/stat.h> 00063 #include <fcntl.h> 00064 //----------------------------------------------- 00065 00066 CANPeakSysUSB::CANPeakSysUSB(const char* cIniFile) 00067 { 00068 m_bInitialized = false; 00069 00070 // read IniFile 00071 m_IniFile.SetFileName(cIniFile, "CanPeakSysUSB.cpp"); 00072 00073 init(); 00074 } 00075 00076 //----------------------------------------------- 00077 CANPeakSysUSB::~CANPeakSysUSB() 00078 { 00079 if (m_bInitialized) 00080 { 00081 CAN_Close(m_handle); 00082 } 00083 } 00084 00085 //----------------------------------------------- 00086 void CANPeakSysUSB::init() 00087 { 00088 std::string sCanDevice; 00089 00090 if( m_IniFile.GetKeyString( "TypeCan", "DevicePath", &sCanDevice, false) != 0) { 00091 sCanDevice = "/dev/pcan32"; 00092 } else std::cout << "CAN-device path read from ini-File: " << sCanDevice << std::endl; 00093 00094 //m_handle = LINUX_CAN_Open("/dev/pcan32", O_RDWR | O_NONBLOCK); 00095 m_handle = LINUX_CAN_Open(sCanDevice.c_str(), O_RDWR); 00096 00097 if (! m_handle) 00098 { 00099 // Fatal error 00100 std::cout << "Cannot open CAN on USB: " << strerror(errno) << std::endl; 00101 sleep(3); 00102 exit(0); 00103 } 00104 00105 m_iBaudrateVal = 0; 00106 m_IniFile.GetKeyInt( "CanCtrl", "BaudrateVal", &m_iBaudrateVal, true); 00107 00108 initCAN(); 00109 } 00110 00111 //------------------------------------------- 00112 bool CANPeakSysUSB::transmitMsg(CanMsg CMsg, bool bBlocking) 00113 { 00114 TPCANMsg TPCMsg; 00115 bool bRet = true; 00116 00117 if (m_bInitialized == false) return false; 00118 00119 // copy CMsg to TPCmsg 00120 TPCMsg.LEN = CMsg.m_iLen; 00121 TPCMsg.ID = CMsg.m_iID; 00122 TPCMsg.MSGTYPE = CMsg.m_iType; 00123 for(int i=0; i<8; i++) 00124 TPCMsg.DATA[i] = CMsg.getAt(i); 00125 00126 //TODO Hier stürtzt die Base ab.. verwende libpcan.h pcan.h um Fehler auszulesen, diagnostizieren, ausgeben und CAN_INIT erneut aufzurufen = neustart can-hardware. 00127 00128 int iRet; 00129 //iRet = CAN_Write(m_handle, &TPCMsg); 00130 iRet = LINUX_CAN_Write_Timeout(m_handle, &TPCMsg, 25); //Timeout in micrsoseconds 00131 00132 if(iRet != CAN_ERR_OK) { 00133 #ifdef __DEBUG__ 00134 std::cout << "CANPeakSysUSB::transmitMsg An error occured while sending..." << iRet << std::endl; 00135 outputDetailedStatus(); 00136 #endif 00137 bRet = false; 00138 } 00139 00140 #ifdef __DEBUG__ 00141 //is this necessary? try iRet==CAN_Status(m_handle) ? 00142 iRet = CAN_Status(m_handle); 00143 00144 if(iRet < 0) 00145 { 00146 std::cout << "CANPeakSysUSB::transmitMsg, system error: " << iRet << std::endl; 00147 bRet = false; 00148 } else if((iRet & CAN_ERR_BUSOFF) != 0) { 00149 std::cout << "CANPeakSysUSB::transmitMsg, BUSOFF detected" << std::endl; 00150 //Try to restart CAN-Device 00151 std::cout << "Trying to re-init Hardware..." << std::endl; 00152 bRet = initCAN(); 00153 00154 } else if((iRet & CAN_ERR_ANYBUSERR) != 0) { 00155 std::cout << "CANPeakSysUSB::transmitMsg, ANYBUSERR" << std::endl; 00156 00157 } else if( (iRet & (~CAN_ERR_QRCVEMPTY)) != 0) { 00158 std::cout << "CANPeakSysUSB::transmitMsg, CAN_STATUS: " << iRet << std::endl; 00159 bRet = false; 00160 } 00161 #endif 00162 00163 return bRet; 00164 } 00165 00166 //------------------------------------------- 00167 bool CANPeakSysUSB::receiveMsg(CanMsg* pCMsg) 00168 { 00169 TPCANRdMsg TPCMsg; 00170 TPCMsg.Msg.LEN = 8; 00171 TPCMsg.Msg.MSGTYPE = 0; 00172 TPCMsg.Msg.ID = 0; 00173 00174 int iRet = CAN_ERR_OK; 00175 00176 bool bRet = false; 00177 00178 if (m_bInitialized == false) return false; 00179 00180 iRet = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, 0); 00181 00182 if (iRet == CAN_ERR_OK) 00183 { 00184 pCMsg->m_iID = TPCMsg.Msg.ID; 00185 pCMsg->set(TPCMsg.Msg.DATA[0], TPCMsg.Msg.DATA[1], TPCMsg.Msg.DATA[2], TPCMsg.Msg.DATA[3], 00186 TPCMsg.Msg.DATA[4], TPCMsg.Msg.DATA[5], TPCMsg.Msg.DATA[6], TPCMsg.Msg.DATA[7]); 00187 bRet = true; 00188 } 00189 else if( (iRet & (~CAN_ERR_QRCVEMPTY)) != 0) //no"empty-queue"-status 00190 { 00191 std::cout << "CANPeakSysUSB::receiveMsg, CAN_STATUS: " << iRet << std::endl; 00192 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0); 00193 } 00194 00195 //catch status messages, these could be further processed in overlying software to identify and handle CAN errors 00196 if( TPCMsg.Msg.MSGTYPE == MSGTYPE_STATUS ) { 00197 std::cout << "CANPeakSysUSB::receiveMsg, status message catched:\nData is (CAN_ERROR_...) " << TPCMsg.Msg.DATA[3] << std::endl; 00198 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0); 00199 } 00200 00201 return bRet; 00202 } 00203 00204 //------------------------------------------- 00205 bool CANPeakSysUSB::receiveMsgRetry(CanMsg* pCMsg, int iNrOfRetry) 00206 { 00207 int i, iRet; 00208 00209 TPCANRdMsg TPCMsg; 00210 TPCMsg.Msg.LEN = 8; 00211 TPCMsg.Msg.MSGTYPE = 0; 00212 TPCMsg.Msg.ID = 0; 00213 00214 if (m_bInitialized == false) return false; 00215 00216 // wait until msg in buffer 00217 bool bRet = true; 00218 iRet = CAN_ERR_OK; 00219 i=0; 00220 do 00221 { 00222 iRet = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, 0); 00223 00224 if(iRet == CAN_ERR_OK) 00225 break; 00226 00227 i++; 00228 usleep(100000); 00229 } 00230 while(i < iNrOfRetry); 00231 00232 // eval return value 00233 if(iRet != CAN_ERR_OK) 00234 { 00235 std::cout << "CANPeakSysUSB::receiveMsgRetry, errorcode= " << nGetLastError() << std::endl; 00236 pCMsg->set(0, 0, 0, 0, 0, 0, 0, 0); 00237 bRet = false; 00238 } 00239 else 00240 { 00241 pCMsg->m_iID = TPCMsg.Msg.ID; 00242 pCMsg->set(TPCMsg.Msg.DATA[0], TPCMsg.Msg.DATA[1], TPCMsg.Msg.DATA[2], TPCMsg.Msg.DATA[3], 00243 TPCMsg.Msg.DATA[4], TPCMsg.Msg.DATA[5], TPCMsg.Msg.DATA[6], TPCMsg.Msg.DATA[7]); 00244 } 00245 00246 return bRet; 00247 } 00248 00249 bool CANPeakSysUSB::initCAN() { 00250 int ret = CAN_ERR_OK; 00251 bool bRet = true; 00252 00253 switch(m_iBaudrateVal) 00254 { 00255 case 0: 00256 ret = CAN_Init(m_handle, CAN_BAUD_1M, CAN_INIT_TYPE_ST); 00257 break; 00258 case 2: 00259 ret = CAN_Init(m_handle, CAN_BAUD_500K, CAN_INIT_TYPE_ST); 00260 break; 00261 case 4: 00262 ret = CAN_Init(m_handle, CAN_BAUD_250K, CAN_INIT_TYPE_ST); 00263 break; 00264 case 6: 00265 ret = CAN_Init(m_handle, CAN_BAUD_125K, CAN_INIT_TYPE_ST); 00266 break; 00267 case 9: 00268 ret = CAN_Init(m_handle, CAN_BAUD_50K, CAN_INIT_TYPE_ST); 00269 break; 00270 case 11: 00271 ret = CAN_Init(m_handle, CAN_BAUD_20K, CAN_INIT_TYPE_ST); 00272 break; 00273 case 13: 00274 ret = CAN_Init(m_handle, CAN_BAUD_10K, CAN_INIT_TYPE_ST); 00275 break; 00276 } 00277 00278 if(ret) 00279 { 00280 std::cout << "CANPeakSysUSB::CANPeakSysUSB(), error in init" << std::endl; 00281 m_bInitialized = false; 00282 bRet = false; 00283 } 00284 else 00285 { 00286 std::cout << "CANPeakSysUSB::CanpeakSys(), init ok" << std::endl; 00287 m_bInitialized = true; 00288 bRet = true; 00289 } 00290 00291 return bRet; 00292 } 00293 00294 void CANPeakSysUSB::outputDetailedStatus() { 00295 TPDIAG diag; 00296 00297 LINUX_CAN_Statistics(m_handle, &diag); 00298 00299 std::cout << "*************************\n" 00300 << "*** Detailed status output of CANPeakSys\n" 00301 << "*************************" 00302 << "\nIRQ-Level: " << diag.wIrqLevel 00303 << "\nNo reads: " << diag.dwReadCounter 00304 << "\nNo writes: " << diag.dwWriteCounter 00305 << "\nNo interrupts: " << diag.dwIRQcounter 00306 << "\nNo errors: " << diag.dwErrorCounter 00307 << "\nError flag: " << diag.wErrorFlag 00308 << "\nLast error: " << diag.nLastError 00309 << std::endl; 00310 }