PCanDevice.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012 SCHUNK GmbH & Co. KG
00003  * Copyright (c) 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004  *
00005  * Licensed under the Apache License, Version 2.0 (the "License");
00006  * you may not use this file except in compliance with the License.
00007  * You may obtain a copy of the License at
00008  *
00009  *   http://www.apache.org/licenses/LICENSE-2.0
00010 
00011  * Unless required by applicable law or agreed to in writing, software
00012  * distributed under the License is distributed on an "AS IS" BASIS,
00013  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014  * See the License for the specific language governing permissions and
00015  * limitations under the License.
00016  */
00017 
00018 #include "PCanDevice.h"
00019 #include <errno.h>
00020 // ========================================================================== ;
00021 //                                                                            ;
00022 // ---- private auxiliary functions ----------------------------------------- ;
00023 //                                                                            ;
00024 // ========================================================================== ;
00025 
00026 // ========================================================================== ;
00027 //                                                                            ;
00028 // ---- protected auxiliary functions --------------------------------------- ;
00029 //                                                                            ;
00030 // ========================================================================== ;
00031 
00032 //possible incomplete
00033 //
00034 
00035 int CPCanDevice::getDeviceError(int iErrorState)
00036 {
00037         int error = ERRID_DEV_WRITEERROR;
00038 
00039         if(((unsigned int)iErrorState & 0xFFFF) & CAN_ERR_QRCVEMPTY)
00040         {
00041                 warning("receive queue is empty");
00042                 error= ERRID_DEV_WRITEERROR;
00043         }
00044         if(iErrorState & CAN_ERR_OVERRUN)
00045         {
00046                 warning("receive buffer overrun");
00047                 error= ERRID_DEV_READERROR;
00048         }
00049         if(iErrorState & CAN_ERR_XMTFULL)
00050         {
00051                 warning("transmit buffer full");
00052                 error =  ERRID_DEV_WRITEERROR;
00053         }
00054         if(iErrorState & CAN_ERR_BUSOFF)
00055         {
00056                 warning("CAN_ERR_OFF_BUS");
00057                 error =  ERRID_DEV_READERROR;
00058         }
00059         if(iErrorState & CAN_ERR_ILLPARAMTYPE )
00060         {
00061                 warning("CAN_ERR_ILLPARAMTYPE");
00062                 error =  ERRID_DEV_READERROR;
00063         }
00064         /*
00065          * no corresponding errors in pcan.h found
00066          *
00067         else if(iErrorState == NTCAN_MESSAGE_LOST)
00068         {
00069                 warning("NTCAN_MESSAGE_LOST");
00070                 return ERRID_DEV_READERROR;
00071         }
00072         else if(iErrorState == NTCAN_RX_TIMEOUT)
00073         {
00074                 warning("NTCAN_RX_TIMEOUT");
00075                 return ERRID_DEV_READTIMEOUT;
00076         }
00077         else if(iErrorState == NTCAN_TX_TIMEOUT)
00078         {
00079                 warning("NTCAN_TX_TIMEOUT");
00080                 return ERRID_DEV_WRITETIMEOUT;
00081         }
00082         */
00083         if(((unsigned int)iErrorState & 0xFFFF) & CAN_ERR_QXMTFULL)
00084         {
00085                 warning("transmit queue full");
00086                 error =  ERRID_DEV_WRITEERROR;
00087         }
00088         if(iErrorState & CAN_ERR_BUSLIGHT)
00089         {
00090                 warning("bus error");
00091                 error =  ERRID_DEV_WRITEERROR;
00092         }
00093         if(((unsigned int)iErrorState & 0xFFFF) & CAN_ERR_BUSHEAVY)
00094         {
00095                 warning("bus error");
00096                 error =  ERRID_DEV_WRITEERROR;
00097         }
00098         if(((unsigned int)iErrorState & 0xFFFF) & CAN_ERR_RESOURCE)
00099         {
00100                 warning("can't create resource");
00101                 error =  ERRID_DEV_WRITEERROR;
00102         }
00103 
00104         return error;
00105 }
00106 
00107 //ok
00108 int CPCanDevice::setBaudRate(unsigned char iBaudRate)
00109 {
00110         m_uiBaudRate = (unsigned long) iBaudRate;
00111         return setBaudRate();
00112 }
00113 
00114 //ok
00115 int CPCanDevice::setBaudRate()
00116 {
00117         /*
00118          * baud rate must be set when initializing can device!
00119          *
00120          * */
00121 
00122         debug(0,"entering CPCanDevice::setBaudRate()...\n");
00123         warning("PCan Device must be reset to set the new baud rate!\n");
00124         
00125         int iRetVal = 0;
00126         m_iErrorState = 0;
00127 
00128         switch( m_iBaudRate )
00129         {
00130                 case 125:
00131                         m_uiBaudRate=CAN_BAUD_125K;     // 125k
00132                         break;
00133                 case 250:
00134                         m_uiBaudRate=CAN_BAUD_250K;     // 250k
00135                         break;
00136                 case 500:
00137                         m_uiBaudRate=CAN_BAUD_500K;     // 500k
00138                         break;
00139                 case 1000:
00140                         m_uiBaudRate=CAN_BAUD_1M;       // 1000k
00141                         break;
00142                 default:
00143                         m_uiBaudRate=CAN_BAUD_250K;     // 250k
00144                         break;
00145         }
00146 
00147         
00148         if (m_bInitFlag)
00149         {
00150                 CAN_Close(m_handle);
00151         }
00152         iRetVal = init(m_uiBaudRate);
00153         debug(0,"InitFlag set to %d\n",m_bInitFlag);
00154         if(iRetVal != CAN_ERR_OK)
00155         {
00156                 warning("can set baudrate 0x%x failed Errorcode: %d", m_uiBaudRate, iRetVal);
00157                 getDeviceError(iRetVal);
00158                 m_iErrorState = ERRID_DEV_INITERROR;
00159                 return m_iErrorState;
00160         }       
00161         else
00162         {
00163           debug(0,"PCanDevice: setting baud rate to %d\n",m_iBaudRate);
00164         }
00165         return m_iErrorState;
00166 }
00167 
00168 //ok
00169 int CPCanDevice::setMessageId(unsigned long uiMessageId)
00170 {
00171         int iRetVal = 0;
00172         m_iErrorState = 0;
00173         //iRetVal = canIdAdd(m_hDevice, uiMessageId);
00174         iRetVal = CAN_MsgFilter(m_handle, uiMessageId ,uiMessageId,MSGTYPE_STANDARD);
00175         if(iRetVal != CAN_ERR_OK)
00176         {
00177                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00178                 getDeviceError(iRetVal);
00179                 m_iErrorState = ERRID_DEV_INITERROR;
00180                 return m_iErrorState;
00181         }
00182         return m_iErrorState;
00183 }
00184 
00185 //ok
00186 int CPCanDevice::clearReadQueue()
00187 {
00188         int iRetVal = 0;
00189         TPCANRdMsg TPCMsg;
00190         
00191         debug(0,"entering CPCanDevice::clearReadQueue()...\n");
00192         TPCMsg.Msg.LEN = 8;
00193         TPCMsg.Msg.MSGTYPE = 0;
00194         TPCMsg.Msg.ID = 0;
00195 
00196         m_iErrorState = 0;
00197         do
00198         {       
00199                 //iRetVal = canRead(m_hDevice, &clESDProtocolMessage, &iNumberOfMessages, NULL);                        
00200                 debug(0,"Trying to read messages ...");
00201                 iRetVal = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, m_uiTimeOut);
00202                 debug(0," 0x%04x\n",iRetVal);
00203 
00204         }while( iRetVal != CAN_ERR_QRCVEMPTY ) ;
00205         
00206         return m_iErrorState;
00207 }
00208 
00209 
00210 //ok
00211 int CPCanDevice::reinit(unsigned char ucBaudRateId)
00212 {
00213 
00214         int  iRetVal = 0;
00215         
00216         m_iErrorState = 0;
00217         if(!m_bInitFlag)
00218         {
00219                 warning("reinit:device not initialized");
00220                 m_iErrorState = ERRID_DEV_NOTINITIALIZED;
00221                 return m_iErrorState;
00222         }
00223         iRetVal = setBaudRate(ucBaudRateId);
00224 
00225         /* done in setBaudRate
00226         switch(ucBaudRateId)
00227         {
00228                 case BAUDRATEID_MOD_CAN_125K:
00229                         m_iBaudRate = 125;
00230                         break;
00231                 case BAUDRATEID_MOD_CAN_250K:
00232                         m_iBaudRate = 250;
00233                         break;
00234                 case BAUDRATEID_MOD_CAN_500K:
00235                         m_iBaudRate = 500;
00236                         break;
00237                 case BAUDRATEID_MOD_CAN_1000K:
00238                         m_iBaudRate = 1000;
00239                         break;
00240         }
00241         iRetVal = canClose(m_hDevice);
00242         if(iRetVal != CAN_ERR_OK)
00243         {
00244                 warning("can close failed Errorcode: %d", iRetVal);
00245                 getDeviceError(iRetVal);
00246                 m_iErrorState = ERRID_DEV_EXITERROR;
00247         }
00248         iRetVal = canClose(m_hSyncDevice);
00249         if(iRetVal != CAN_ERR_OK)
00250         {
00251                 warning("can close failed Errorcode: %d", iRetVal);
00252                 getDeviceError(iRetVal);
00253                 m_iErrorState = ERRID_DEV_EXITERROR;
00254         }
00255         m_bInitFlag = false;
00256         iRetVal = canOpen(      
00257                                 m_iDeviceId,                    // Net
00258                                 0,                                              // Mode
00259                                 m_uiQueueSize,                  // TX Queue
00260                                 m_uiQueueSize,                  // RX Queue
00261                                 20*m_uiTimeOut,                 // Tx Timeout
00262                                 m_uiTimeOut,                    // Rx Timeout
00263                                 &m_hDevice);
00264         if(iRetVal != CAN_ERR_OK)
00265         {
00266                 warning("can open failed Errorcode: %d", iRetVal);
00267                 getDeviceError(iRetVal);
00268                 m_iErrorState = ERRID_DEV_INITERROR;
00269                 return m_iErrorState;
00270         }
00271         */
00272 
00273         //iRetVal = canIdAdd(m_hDevice, (MSGID_ACK + i));
00274         iRetVal = CAN_MsgFilter(m_handle, MSGID_ACK ,MSGID_ACK+m_iModuleCountMax,MSGTYPE_STANDARD);
00275         if(iRetVal != CAN_ERR_OK)
00276         {
00277                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00278                 getDeviceError(iRetVal);
00279                 m_iErrorState = ERRID_DEV_INITERROR;
00280                 return m_iErrorState;
00281         }
00282         //iRetVal = canIdAdd(m_hDevice, (MSGID_STATE + i));
00283         iRetVal = CAN_MsgFilter(m_handle, MSGID_STATE ,MSGID_STATE+m_iModuleCountMax,MSGTYPE_STANDARD);
00284         if(iRetVal != CAN_ERR_OK)
00285         {
00286                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00287                 getDeviceError(iRetVal);
00288                 m_iErrorState = ERRID_DEV_INITERROR;
00289                 return m_iErrorState;
00290         }
00291 
00292         //iRetVal = canIdAdd(m_hDevice, (MSGID_MP55_RECV + i));
00293         iRetVal = CAN_MsgFilter(m_handle, MSGID_MP55_RECV ,MSGID_MP55_RECV+MAX_MP55,MSGTYPE_STANDARD);
00294         if(iRetVal != CAN_ERR_OK)
00295         {
00296                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00297                 getDeviceError(iRetVal);
00298                 m_iErrorState = ERRID_DEV_INITERROR;
00299                 return m_iErrorState;
00300         }
00301 
00302         //iRetVal = canIdAdd(m_hDevice, (0x180 + i));
00303         iRetVal = CAN_MsgFilter(m_handle, 0x180 ,0x180+MAX_MP55,MSGTYPE_STANDARD);
00304         if(iRetVal != CAN_ERR_OK)
00305         {
00306                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00307                 getDeviceError(iRetVal);
00308                 m_iErrorState = ERRID_DEV_INITERROR;
00309                 return m_iErrorState;
00310         }
00311 
00312         //iRetVal = canIdAdd(m_hDevice, (MSGID_SCHUNK_RECV + i));
00313         iRetVal = CAN_MsgFilter(m_handle, MSGID_SCHUNK_RECV ,MSGID_SCHUNK_RECV+MAX_SCHUNK,MSGTYPE_STANDARD);
00314         if(iRetVal != CAN_ERR_OK)
00315         {
00316                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00317                 getDeviceError(iRetVal);
00318                 m_iErrorState = ERRID_DEV_INITERROR;
00319                 return m_iErrorState;
00320         }
00321 
00322         //iRetVal = canIdAdd(m_hSyncDevice, MSGID_ALL);
00323         iRetVal = CAN_MsgFilter(m_handle, MSGID_ALL ,MSGID_ALL,MSGTYPE_STANDARD);
00324         if(iRetVal != CAN_ERR_OK)
00325         {
00326                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00327                 getDeviceError(iRetVal);
00328                 m_iErrorState = ERRID_DEV_INITERROR;
00329                 return m_iErrorState;
00330         }
00331 
00332         m_iErrorState = clearReadQueue();
00333         if(m_iErrorState != 0)
00334                 return m_iErrorState;
00335 
00336         if(m_iErrorState == 0)
00337         {
00338                 m_bInitFlag = true;
00339         }
00340 
00341         
00342         updateModuleIdMap();
00343         return m_iErrorState;
00344 }
00345 
00346 
00347 
00348 int CPCanDevice::readDevice(CProtocolMessage& rclProtocolMessage)
00349 {
00350         int iRetVal = 0;
00351         
00352         TPCANRdMsg TPCMsg;
00353         TPCMsg.Msg.LEN = 8;
00354         TPCMsg.Msg.MSGTYPE = 0;
00355         TPCMsg.Msg.ID = 0;
00356 
00357         m_iErrorState = 0;
00358         int no = 0;
00359         do
00360         {
00361                 m_iErrorState = 0;
00362                 iRetVal = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, m_uiTimeOut);
00363                 if (iRetVal == CAN_ERR_OK)
00364                   break;
00365                 else
00366                   CAN_Status(m_handle);
00367                 no++;
00368 
00369                 m_iErrorState = getDeviceError(iRetVal);
00370                 debug(2,"Read error (%s), attempt %d of %d",strerror(nGetLastError()),no,m_iNoOfRetries+1);
00371                 //sleep(100);
00372         }while (no <= m_iNoOfRetries);
00373         if (iRetVal == CAN_ERR_OK)
00374         {
00375                 rclProtocolMessage.m_uiMessageId = TPCMsg.Msg.ID;
00376                 rclProtocolMessage.m_ucMessageLength = TPCMsg.Msg.LEN;
00377                 memcpy(rclProtocolMessage.m_aucMessageData, TPCMsg.Msg.DATA, rclProtocolMessage.m_ucMessageLength);
00378                 printMessage(rclProtocolMessage,READ);
00379         }
00380         else
00381         {
00382                 //warning("Last Error reported: %s",strerror(nGetLastError()));
00383                 //m_iErrorState = getDeviceError(iRetVal);
00384                 warning("CAN read failed Errorcode: 0x%04x", iRetVal);
00385 //              return m_iErrorState;
00386         }
00387         return m_iErrorState;
00388 }
00389 
00390 
00391 //ok
00392 int CPCanDevice::writeDevice(CProtocolMessage& rclProtocolMessage)
00393 {
00394         int iRetVal = 0;
00395         TPCANMsg TPCMsg;
00396         
00397         TPCMsg.MSGTYPE = MSGTYPE_STANDARD;
00398         m_iErrorState = 0;
00399         TPCMsg.ID = rclProtocolMessage.m_uiMessageId;
00400         printMessage(rclProtocolMessage,WRITE);
00401                                                                               
00402         TPCMsg.LEN =  rclProtocolMessage.m_ucMessageLength;
00403         if(rclProtocolMessage.m_bRTRFlag)
00404                 TPCMsg.MSGTYPE = MSGTYPE_RTR;
00405         memcpy(TPCMsg.DATA, rclProtocolMessage.m_aucMessageData, rclProtocolMessage.m_ucMessageLength);
00406         iRetVal = CAN_Write(m_handle, &TPCMsg);
00407         if(iRetVal != CAN_ERR_OK)
00408         {
00409                 warning("can send failed Errorcode:0x%04x", iRetVal);
00410                 m_iErrorState = getDeviceError(iRetVal);
00411                 //return m_iErrorState;
00412         }
00413         iRetVal = CAN_Status(m_handle);
00414         if (iRetVal < 0)
00415         {
00416                 warning("Last Error reported: %s",strerror(nGetLastError()));
00417                 m_iErrorState = ERRID_DEV_WRITEERROR;
00418         }
00419 
00420         return m_iErrorState;
00421 }
00422 
00423 // ========================================================================== ;
00424 //                                                                            ;
00425 // ---- constructors / destructor ------------------------------------------- ;
00426 //                                                                            ;
00427 // ========================================================================== ;
00428 
00429 CPCanDevice::CPCanDevice() : m_hDevice(0), m_hSyncDevice(0), m_iDeviceId(-1), m_uiBaudRate(0), m_uiQueueSize(128), m_uiTimeOut(3)               // ESD C331
00430 {
00431         initMessage("CPCanDevice", g_iDebugLevel, g_bDebug, g_bDebugFile);
00432         m_DeviceName = (char*) malloc(200 * sizeof(char));
00433         memset(m_DeviceName,0,sizeof(m_DeviceName));
00434 }
00435 
00436 CPCanDevice::CPCanDevice(const CPCanDevice& rclPCanDevice)
00437 {
00438         error(-1, "Sorry constructor is not implemented");
00439 }
00440 
00441 CPCanDevice::~CPCanDevice()
00442 {
00443         free(m_DeviceName);
00444         if (m_bInitFlag)
00445           this->exit();
00446 }
00447 
00448 // ========================================================================== ;
00449 //                                                                            ;
00450 // ---- operators ----------------------------------------------------------- ;
00451 //                                                                            ;
00452 // ========================================================================== ;
00453 
00454 CPCanDevice& CPCanDevice::operator=(const CPCanDevice& rclPCanDevice)
00455 {
00456         error(-1, "Sorry operator= is not implemented");
00457         return *this;
00458 }
00459 
00460 // ========================================================================== ;
00461 //                                                                            ;
00462 // ---- query functions ----------------------------------------------------- ;
00463 //                                                                            ;
00464 // ========================================================================== ;
00465 
00466 // ========================================================================== ;
00467 //                                                                            ;
00468 // ---- modify functions ---------------------------------------------------- ;
00469 //                                                                            ;
00470 // ========================================================================== ;
00471 
00472 void CPCanDevice::setQueueSize(unsigned short uiQueueSize)
00473 {
00474         m_uiQueueSize = uiQueueSize;
00475 }
00476 
00477 void CPCanDevice::setTimeOut(unsigned long uiTimeOut)
00478 {
00479         m_uiTimeOut= uiTimeOut;
00480 }
00481 
00482 // ========================================================================== ;
00483 //                                                                            ;
00484 // ---- I/O functions ------------------------------------------------------- ;
00485 //                                                                            ;
00486 // ========================================================================== ;
00487 
00488 // ========================================================================== ;
00489 //                                                                            ;
00490 // ---- exec functions ------------------------------------------------------ ;
00491 //                                                                            ;
00492 // ========================================================================== ;
00493 
00494 //ok
00495 int CPCanDevice::init()
00496 {
00497         return init(CAN_BAUD_250K);
00498 }
00499 int CPCanDevice::init(unsigned long baudRate)
00500 {
00501         int iRetVal = CAN_ERR_OK;
00502         printf("Initializing pcan device ...\n");
00503         //m_handle = LINUX_CAN_Open("/dev/pcan32", O_RDWR);
00504         m_handle = LINUX_CAN_Open(m_DeviceName,0);
00505 
00506         if (! m_handle)
00507         {
00508                 // Fatal error
00509                 printf("Error: Cannot open CAN on USB (%s): %s\n", m_DeviceName, strerror(errno));
00510                 iRetVal = -1;
00511         }
00512         else
00513         {
00514                 iRetVal = CAN_Init(m_handle, baudRate, CAN_INIT_TYPE_ST);
00515         }
00516         if(iRetVal != CAN_ERR_OK)
00517         {
00518                 printf("PcanDevice: error in init" );
00519         }
00520         else
00521         {
00522                 printf("PcanDevice, init ok\n" );
00523                 m_bInitFlag = true;
00524         }
00525         return iRetVal;
00526 }
00527 
00528 /*
00529  * Not needed for pcan
00530  */
00531 int CPCanDevice::init(const char* acInitString)
00532 {
00533         InitializeCriticalSection(&m_csDevice);
00534         int iRetVal = 0;
00535         m_uiTimeOut = 100;
00536         m_iNoOfRetries = 10;
00537         char* pcToken;
00538         char acString[128];
00539         int deb = getDebugLevel();
00540         if (deb > 0)
00541         {
00542                 printf("CPCanDevice::init: DebugLevel: %d\n",deb);
00543                 printf("writing debug output to file debug.txt!\n");
00544         }
00545         debug(0,"entering CPCanDevice::init(const char* acInitString) ...\n");
00546         if(m_bInitFlag)
00547         {
00548                 warning("device already initialized");
00549                 m_iErrorState = ERRID_DEV_ISINITIALIZED;
00550                 return m_iErrorState;
00551         }
00552         m_iDeviceId = -1;
00553         m_iErrorState = 0;
00554         strncpy(m_acInitString,acInitString,128);
00555         strncpy(acString,acInitString,128);
00556         pcToken = strtok( acString, ":" );
00557         if( !pcToken )
00558         {       m_iErrorState = ERRID_DEV_BADINITSTRING;
00559                 return m_iErrorState;
00560         }
00561         if( strcmp( pcToken, "PCAN" ) != 0 )
00562         {       m_iErrorState = ERRID_DEV_BADINITSTRING;
00563                 return m_iErrorState;
00564         }
00565         pcToken = strtok( NULL, "," );
00566         if( !pcToken )
00567         {       m_iErrorState = ERRID_DEV_BADINITSTRING;
00568                 return m_iErrorState;
00569         }
00570 
00571 
00572         
00573         
00574         m_iDeviceId = atoi(pcToken);
00575         //std::cout << m_iDeviceId << std::endl;
00576 
00577 
00578         strncpy(m_DeviceName,pcToken,12);
00579         
00580         /*
00581         
00582         if (m_iDeviceId == 0)
00583         {
00584                 strcpy(m_DeviceName,"/dev/pcan32");
00585         }
00586         else if (m_iDeviceId == 1)
00587         {
00588                 strcpy(m_DeviceName,"/dev/pcan33");
00589         }
00590         else if (m_iDeviceId == 14)
00591         {
00592                 strcpy(m_DeviceName,"/dev/pcan0");
00593         }
00594         else if (m_iDeviceId == 15)
00595         {
00596                 strcpy(m_DeviceName,"/dev/pcan1");
00597         }
00598         else if (m_iDeviceId == 16)
00599         {
00600                 strcpy(m_DeviceName,"/dev/pcan2");
00601         }
00602         else if (m_iDeviceId == 17)
00603         {
00604                 strcpy(m_DeviceName,"/dev/pcan3");
00605         }
00606         else
00607         {
00608                 printf("Warning: currently only support for 2 devices!\n");
00609         }
00610         */
00611         
00612         //printf("Device %s: %s\n",pcToken,m_DeviceName);
00613 
00614 
00615         pcToken = strtok( NULL, "," );
00616         if( !pcToken )
00617         {       m_iErrorState = ERRID_DEV_BADINITSTRING;
00618                 return m_iErrorState;
00619         }
00620         m_iBaudRate = atoi(pcToken);
00621 
00622 
00623         try
00624         {
00625                 m_handle = LINUX_CAN_Open(m_DeviceName,0);
00626                 if (! m_handle)
00627                 {
00628                         // Fatal error
00629                         printf("Error: Cannot open CAN on USB (%s): %s\n", m_DeviceName, strerror(errno));
00630                         iRetVal = -1;
00631                 }
00632                 else
00633                 {
00634                         printf("PCanDevice successfully opened on %s\n",m_DeviceName);
00635                 }
00636         }
00637         catch(...)
00638         {
00639                         warning("open PCAN device failed no library found");
00640                         m_iErrorState = ERRID_DEV_NOLIBRARY;
00641                         return m_iErrorState;
00642         }
00643 
00644 
00645         iRetVal = CAN_MsgFilter(m_handle, MSGID_ACK ,MSGID_ACK+m_iModuleCountMax,MSGTYPE_STANDARD);
00646         if(iRetVal != CAN_ERR_OK)
00647         {
00648                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00649                 getDeviceError(iRetVal);
00650                 m_iErrorState = ERRID_DEV_INITERROR;
00651                 return m_iErrorState;
00652         }
00653         //iRetVal = canIdAdd(m_hDevice, (MSGID_STATE + i));
00654         iRetVal = CAN_MsgFilter(m_handle, MSGID_STATE ,MSGID_STATE+m_iModuleCountMax,MSGTYPE_STANDARD);
00655         if(iRetVal != CAN_ERR_OK)
00656         {
00657                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00658                 getDeviceError(iRetVal);
00659                 m_iErrorState = ERRID_DEV_INITERROR;
00660                 return m_iErrorState;
00661         }
00662 
00663         //iRetVal = canIdAdd(m_hDevice, (MSGID_MP55_RECV + i));
00664         iRetVal = CAN_MsgFilter(m_handle, MSGID_MP55_RECV ,MSGID_MP55_RECV+MAX_MP55,MSGTYPE_STANDARD);
00665         if(iRetVal != CAN_ERR_OK)
00666         {
00667                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00668                 getDeviceError(iRetVal);
00669                 m_iErrorState = ERRID_DEV_INITERROR;
00670                 return m_iErrorState;
00671         }
00672 
00673         //iRetVal = canIdAdd(m_hDevice, (0x180 + i));
00674         iRetVal = CAN_MsgFilter(m_handle, 0x180 ,0x180+MAX_MP55,MSGTYPE_STANDARD);
00675         if(iRetVal != CAN_ERR_OK)
00676         {
00677                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00678                 getDeviceError(iRetVal);
00679                 m_iErrorState = ERRID_DEV_INITERROR;
00680                 return m_iErrorState;
00681         }
00682 
00683         //iRetVal = canIdAdd(m_hDevice, (MSGID_SCHUNK_RECV + i));
00684         iRetVal = CAN_MsgFilter(m_handle, MSGID_SCHUNK_RECV ,MSGID_SCHUNK_RECV+MAX_SCHUNK,MSGTYPE_STANDARD);
00685         if(iRetVal != CAN_ERR_OK)
00686         {
00687                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00688                 getDeviceError(iRetVal);
00689                 m_iErrorState = ERRID_DEV_INITERROR;
00690                 return m_iErrorState;
00691         }
00692 
00693         //iRetVal = canIdAdd(m_hSyncDevice, MSGID_ALL);
00694         iRetVal = CAN_MsgFilter(m_handle, MSGID_ALL ,MSGID_ALL,MSGTYPE_STANDARD);
00695         if(iRetVal != CAN_ERR_OK)
00696         {
00697                 warning("Can_MsgFilter failed Errorcode: %d", iRetVal);
00698                 getDeviceError(iRetVal);
00699                 m_iErrorState = ERRID_DEV_INITERROR;
00700                 return m_iErrorState;
00701         }
00702         
00703 
00704         m_iErrorState = setBaudRate();
00705         if(m_iErrorState != 0)
00706                 return m_iErrorState;
00707 
00708         m_iErrorState = clearReadQueue();
00709         if(m_iErrorState != 0)
00710                 return m_iErrorState;
00711 
00712         if(m_iErrorState == 0)
00713         {
00714                 m_bInitFlag = true;
00715                 debug(0,"PCanDevice:init successfull!\n");
00716         }
00717         updateModuleIdMap();
00718 
00719         return m_iErrorState;
00720 }
00721 
00722 
00723 
00724 //ok
00725 int CPCanDevice::exit()
00726 {
00727         int iRetVal = 0;
00728         m_iErrorState = 0;
00729 
00730         //printf diagnosis
00731         //i
00732         TPDIAG Diag;
00733         iRetVal = LINUX_CAN_Statistics(m_handle,&Diag);
00734         debug(0,"PCanDevice: exit():");
00735         debug(0,"--------------STATISTICS-------------------");
00736         debug(0,"Total number of reads: %d",Diag.dwReadCounter);
00737         debug(0,"Total number of writes: %d",Diag.dwWriteCounter);
00738         debug(0,"Total number of interrupts: %d",Diag.dwIRQcounter);
00739         debug(0,"Total number of errors: %d",Diag.dwErrorCounter);
00740         debug(0,"Error flag: 0x%04x",Diag.wErrorFlag);
00741         
00742         if(!m_bInitFlag)
00743         {
00744                 warning("exit:device not initialized");
00745                 m_iErrorState = ERRID_DEV_NOTINITIALIZED;
00746                 return m_iErrorState;
00747         }
00748         EnterCriticalSection(&m_csDevice);
00749         iRetVal = CAN_ERR_OK;
00750         iRetVal = CAN_Close(m_handle);
00751         if(iRetVal != CAN_ERR_OK)
00752         {
00753                 warning("can close failed Errorcode: %d", iRetVal);
00754                 getDeviceError(iRetVal);
00755                 m_iErrorState = ERRID_DEV_EXITERROR;
00756         }
00757         m_bInitFlag = false;
00758         LeaveCriticalSection(&m_csDevice);
00759         DeleteCriticalSection(&m_csDevice);
00760         return m_iErrorState;
00761 }
00762 
00763 int CPCanDevice::waitForStartMotionAll()
00764 {
00765         int iRetVal = 0;
00766         bool bRecieved = false;
00767         TPCANRdMsg TPCMsg;
00768         TPCMsg.Msg.LEN = 8;
00769         TPCMsg.Msg.MSGTYPE = 0;
00770         TPCMsg.Msg.ID = 0;
00771 
00772         m_iErrorState = 0;
00773         iRetVal = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, m_uiTimeOut);
00774 
00775         m_iErrorState = 0;
00776 
00777         do
00778         {       
00779                 //iRetVal = canRead(m_hSyncDevice, &clESDProtocolMessage, &iNumberOfMessages, NULL);                    
00780                 iRetVal = LINUX_CAN_Read_Timeout(m_handle, &TPCMsg, m_uiTimeOut);
00781                 if(iRetVal != CAN_ERR_OK)
00782                 {
00783                         warning("can read failed Errorcode: 0x%04x", iRetVal);
00784                         m_iErrorState = getDeviceError(iRetVal);
00785                         return m_iErrorState;
00786                 }
00787                 bRecieved = true;
00788                 if(TPCMsg.Msg.ID != MSGID_ALL)
00789                 {
00790                         debug(1, "received CAN-ID %x, expected %x", TPCMsg.Msg.ID, MSGID_ALL);
00791                         bRecieved = false;
00792                 }
00793                 if(TPCMsg.Msg.DATA[0] != CMDID_STARTMOVE)
00794                 {
00795                         debug(1, "wrong command ID");
00796                         bRecieved = false;
00797                 }
00798         }
00799         while(!bRecieved);
00800         return m_iErrorState;
00801 }
00802 


schunk_libm5api
Author(s): Florian Weisshardt
autogenerated on Sat Jun 8 2019 20:25:13