$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: cob_driver 00012 * ROS package name: cob_canopen_motor 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: - Assign Adsress of digital input for homing switch "iHomeDigIn" via parameters (in evalReceived Message, Line 116). 00022 * - Homing Event should be defined by a parameterfile and handed to CanDrive... e.g. via the DriveParam.h (in inithoming, Line 531). 00023 * - Check whether "requestStatus" can/should be done in the class implementing the component 00024 * 00025 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00026 * 00027 * Redistribution and use in source and binary forms, with or without 00028 * modification, are permitted provided that the following conditions are met: 00029 * 00030 * * Redistributions of source code must retain the above copyright 00031 * notice, this list of conditions and the following disclaimer. 00032 * * Redistributions in binary form must reproduce the above copyright 00033 * notice, this list of conditions and the following disclaimer in the 00034 * documentation and/or other materials provided with the distribution. 00035 * * Neither the name of the Fraunhofer Institute for Manufacturing 00036 * Engineering and Automation (IPA) nor the names of its 00037 * contributors may be used to endorse or promote products derived from 00038 * this software without specific prior written permission. 00039 * 00040 * This program is free software: you can redistribute it and/or modify 00041 * it under the terms of the GNU Lesser General Public License LGPL as 00042 * published by the Free Software Foundation, either version 3 of the 00043 * License, or (at your option) any later version. 00044 * 00045 * This program is distributed in the hope that it will be useful, 00046 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00047 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00048 * GNU Lesser General Public License LGPL for more details. 00049 * 00050 * You should have received a copy of the GNU Lesser General Public 00051 * License LGPL along with this program. 00052 * If not, see <http://www.gnu.org/licenses/>. 00053 * 00054 ****************************************************************/ 00055 00056 00057 #include <assert.h> 00058 #include <cob_canopen_motor/CanDriveHarmonica.h> 00059 00060 //----------------------------------------------- 00061 CanDriveHarmonica::CanDriveHarmonica() 00062 { 00063 // Parameter 00064 m_Param.iDivForRequestStatus = 10; 00065 m_Param.dCanTimeout = 6; 00066 00067 // Variables 00068 m_pCanCtrl = NULL; 00069 00070 m_iStatusCtrl = 0; 00071 m_dPosGearMeasRad = 0; 00072 m_dAngleGearRadMem = 0; 00073 m_dVelGearMeasRadS = 0; 00074 00075 m_VelCalcTime.SetNow(); 00076 00077 m_bLimSwLeft = false; 00078 m_bLimSwRight = false; 00079 00080 m_bLimitSwitchEnabled = false; 00081 00082 m_iCountRequestDiv = 0; 00083 00084 m_iMotorState = ST_PRE_INITIALIZED; 00085 m_bCurrentLimitOn = false; 00086 00087 m_iNumAttempsRecFail = 0; 00088 00089 m_SendTime.SetNow(); 00090 m_StartTime.SetNow(); 00091 00092 m_bOutputOfFailure = false; 00093 00094 m_bIsInitialized = false; 00095 00096 00097 ElmoRec = new ElmoRecorder(this); 00098 00099 } 00100 00101 //----------------------------------------------- 00102 void CanDriveHarmonica::setCanOpenParam( int iTxPDO1, int iTxPDO2, int iRxPDO2, int iTxSDO, int iRxSDO ) 00103 { 00104 m_ParamCanOpen.iTxPDO1 = iTxPDO1; 00105 m_ParamCanOpen.iTxPDO2 = iTxPDO2; 00106 m_ParamCanOpen.iRxPDO2 = iRxPDO2; 00107 m_ParamCanOpen.iTxSDO = iTxSDO; 00108 m_ParamCanOpen.iRxSDO = iRxSDO; 00109 00110 } 00111 00112 //----------------------------------------------- 00113 bool CanDriveHarmonica::evalReceivedMsg(CanMsg& msg) 00114 { 00115 bool bRet = false; 00116 int iDigIn; 00117 int iFailure; 00118 int iPara; 00119 00120 int iHomeDigIn = 0x0001; // 0x0001 for CoB3 steering drive homing input; 0x0400 for Scara 00121 int iTemp1, iTemp2; 00122 00123 m_CanMsgLast = msg; 00124 00125 //----------------------- 00126 // eval answers from PDO1 - transmitted on SYNC msg 00127 if (msg.m_iID == m_ParamCanOpen.iTxPDO1) 00128 { 00129 iTemp1 = (msg.getAt(3) << 24) | (msg.getAt(2) << 16) 00130 | (msg.getAt(1) << 8) | (msg.getAt(0) ); 00131 00132 m_dPosGearMeasRad = m_DriveParam.getSign() * m_DriveParam. 00133 PosMotIncrToPosGearRad(iTemp1); 00134 00135 iTemp2 = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00136 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00137 00138 m_dVelGearMeasRadS = m_DriveParam.getSign() * m_DriveParam. 00139 VelMotIncrPeriodToVelGearRadS(iTemp2); 00140 00141 m_WatchdogTime.SetNow(); 00142 00143 bRet = true; 00144 } 00145 00146 //----------------------- 00147 // eval answers from binary interpreter 00148 if (msg.m_iID == m_ParamCanOpen.iTxPDO2) 00149 { 00150 if( (msg.getAt(0) == 'P') && (msg.getAt(1) == 'X') ) // current pos 00151 { 00152 } 00153 00154 else if( (msg.getAt(0) == 'P') && (msg.getAt(1) == 'A') ) // position absolute 00155 { 00156 } 00157 00158 else if( (msg.getAt(0) == 'J') && (msg.getAt(1) == 'V') ) // current velocity 00159 { 00160 } 00161 00162 else if( (msg.getAt(0) == 'B') && (msg.getAt(1) == 'G') ) // begin motion 00163 { 00164 } 00165 00166 else if( (msg.getAt(0) == 'U') && (msg.getAt(1) == 'M') ) // user mode 00167 { 00168 iDigIn = 0x1FFFFF & ( (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00169 | (msg.getAt(5) << 8) | (msg.getAt(4)) ); 00170 } 00171 00172 else if( (msg.getAt(0) == 'I') && (msg.getAt(1) == 'P') ) // digital in == limit switches 00173 { 00174 iDigIn = 0x1FFFFF & ( (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00175 | (msg.getAt(5) << 8) | (msg.getAt(4)) ); 00176 iDigIn = 0x1FFFFF & ( (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00177 | (msg.getAt(5) << 8) | (msg.getAt(4)) ); 00178 00179 if( (iDigIn & iHomeDigIn) != 0x0000 ) 00180 { 00181 m_bLimSwRight = true; 00182 } 00183 } 00184 00185 else if( (msg.getAt(0) == 'S') && (msg.getAt(1) == 'R') ) // status 00186 { 00187 m_iStatusCtrl = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00188 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00189 00190 evalStatusRegister(m_iStatusCtrl); 00191 ElmoRec->readoutRecorderTryStatus(m_iStatusCtrl, seg_Data); 00192 00193 } 00194 00195 else if( (msg.getAt(0) == 'M') && (msg.getAt(1) == 'F') ) // motor failure 00196 { 00197 iFailure = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00198 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00199 00200 evalMotorFailure(iFailure); 00201 } 00202 00203 // debug eval 00204 else if( (msg.getAt(0) == 'U') && (msg.getAt(1) == 'M') ) 00205 { 00206 iPara = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00207 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00208 00209 std::cout << "um " << iPara << std::endl; 00210 } 00211 00212 else if( (msg.getAt(0) == 'P') && (msg.getAt(1) == 'M') ) 00213 { 00214 iPara = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00215 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00216 00217 std::cout << "pm " << iPara << std::endl; 00218 } 00219 00220 else if( (msg.getAt(0) == 'A') && (msg.getAt(1) == 'C') ) 00221 { 00222 iPara = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00223 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00224 00225 std::cout << "ac " << iPara << std::endl; 00226 } 00227 00228 else if( (msg.getAt(0) == 'D') && (msg.getAt(1) == 'C') ) 00229 { 00230 iPara = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00231 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00232 00233 std::cout << "dc " << iPara << std::endl; 00234 } 00235 else if( (msg.getAt(0) == 'H') && (msg.getAt(1) == 'M') ) 00236 { 00237 // status message (homing armed = 1 / disarmed = 0) is encoded in 5th byte 00238 if(msg.getAt(4) == 0) 00239 { 00240 // if 0 received: elmo disarmed homing after receiving the defined event 00241 m_bLimSwRight = true; 00242 } 00243 } 00244 else if( (msg.getAt(0) == 'I') && (msg.getAt(1) == 'Q') ) 00245 { 00246 int iVal=0; 00247 iVal = (msg.getAt(7) << 24) | (msg.getAt(6) << 16) 00248 | (msg.getAt(5) << 8) | (msg.getAt(4) ); 00249 float* pfVal; 00250 pfVal=(float*)&iVal; 00251 m_dMotorCurr = *pfVal; 00252 } 00253 00254 else 00255 { 00256 } 00257 00258 m_WatchdogTime.SetNow(); 00259 00260 bRet = true; 00261 } 00262 00263 //----------------------- 00264 // eval answer from SDO 00265 if (msg.m_iID == m_ParamCanOpen.iTxSDO) 00266 { 00267 m_WatchdogTime.SetNow(); 00268 00269 if( (msg.getAt(0) >> 5) == 0) { //Received Upload SDO Segment (scs = 0) 00270 //std::cout << "SDO Upload Segment received" << std::endl; 00271 receivedSDODataSegment(msg); 00272 00273 } else if( (msg.getAt(0) & 0xE2) == 0x40) { //Received Initiate SDO Upload, that is not expedited -> start segmented upload (scs = 2 AND expedited flag = 0) 00274 //std::cout << "SDO Initiate Segmented Upload received, Object ID: " << (msg.getAt(1) | (msg.getAt(2) << 8) ) << std::endl; 00275 receivedSDOSegmentedInitiation(msg); 00276 00277 } else if( (msg.getAt(0) >> 5) == 4) { // Received an Abort SDO Transfer message, cs = 4 00278 unsigned int iErrorNum = (msg.getAt(4) | msg.getAt(5) << 8 | msg.getAt(6) << 16 | msg.getAt(7) << 24); 00279 receivedSDOTransferAbort(iErrorNum); 00280 } 00281 00282 bRet = true; 00283 } 00284 00285 return bRet; 00286 } 00287 00288 //----------------------------------------------- 00289 bool CanDriveHarmonica::init() 00290 { 00291 int iCnt, iPosCnt; 00292 bool bRet = true; 00293 CanMsg Msg; 00294 00295 m_iMotorState = ST_PRE_INITIALIZED; 00296 00297 00298 // Set Values for Modulo-Counting. Neccessary to preserve absolute position for homed motors (after encoder overflow) 00299 int iIncrRevWheel = int( (double)m_DriveParam.getGearRatio() * (double)m_DriveParam.getBeltRatio() 00300 * (double)m_DriveParam.getEncIncrPerRevMot() * 3 ); 00301 IntprtSetInt(8, 'M', 'O', 0, 0); 00302 usleep(20000); 00303 IntprtSetInt(8, 'X', 'M', 2, iIncrRevWheel * 5000); 00304 usleep(20000); 00305 IntprtSetInt(8, 'X', 'M', 1, -iIncrRevWheel * 5000); 00306 usleep(20000); 00307 00308 00309 setTypeMotion(MOTIONTYPE_VELCTRL); 00310 // ---------- set position counter to zero 00311 IntprtSetInt(8, 'P', 'X', 0, 0); 00312 00313 iCnt = 0; 00314 while(true) 00315 { 00316 m_pCanCtrl->receiveMsg(&Msg); 00317 00318 if( (Msg.getAt(0) == 'P') && (Msg.getAt(1) == 'X') ) 00319 { 00320 iPosCnt = (Msg.getAt(7) << 24) | (Msg.getAt(6) << 16) 00321 | (Msg.getAt(5) << 8) | (Msg.getAt(4) ); 00322 00323 m_dPosGearMeasRad = m_DriveParam.getSign() * m_DriveParam.PosMotIncrToPosGearRad(iPosCnt); 00324 m_dAngleGearRadMem = m_dPosGearMeasRad; 00325 break; 00326 } 00327 00328 if ( iCnt > 300 ) 00329 { 00330 std::cout << "CanDriveHarmonica: initial position not set" << std::endl; 00331 bRet = false; 00332 break; 00333 } 00334 00335 usleep(10000); 00336 iCnt++; 00337 } 00338 00339 // ---------- set PDO mapping 00340 // Mapping of TPDO1: 00341 // - position 00342 // - velocity 00343 00344 // stop all emissions of TPDO1 00345 sendSDODownload(0x1A00, 0, 0); 00346 00347 // position 4 byte of TPDO1 00348 sendSDODownload(0x1A00, 1, 0x60640020); 00349 00350 // velocity 4 byte of TPDO1 00351 sendSDODownload(0x1A00, 2, 0x60690020); 00352 00353 // transmission type "synch" 00354 sendSDODownload(0x1800, 2, 1); 00355 00356 // activate mapped objects 00357 sendSDODownload(0x1A00, 0, 2); 00358 00359 m_bWatchdogActive = false; 00360 00361 if( bRet ) 00362 m_bIsInitialized = true; 00363 00364 return bRet; 00365 } 00366 //----------------------------------------------- 00367 bool CanDriveHarmonica::stop() 00368 { 00369 bool bRet = true; 00370 // motor off 00371 IntprtSetInt(8, 'M', 'O', 0, 0); 00372 usleep(20000); 00373 return bRet; 00374 } 00375 //----------------------------------------------- 00376 bool CanDriveHarmonica::start() 00377 { 00378 // motor on 00379 IntprtSetInt(8, 'M', 'O', 0, 1); 00380 usleep(20000); 00381 00382 // ------------------- request status 00383 int iCnt; 00384 bool bRet = true; 00385 int iStatus; 00386 CanMsg Msg; 00387 00388 // clear the can buffer 00389 do 00390 { 00391 bRet = m_pCanCtrl->receiveMsg(&Msg); 00392 } 00393 while(bRet == true); 00394 00395 // send request 00396 IntprtSetInt(4, 'S', 'R', 0, 0); 00397 00398 iCnt = 0; 00399 while(true) 00400 { 00401 m_pCanCtrl->receiveMsg(&Msg); 00402 00403 if( (Msg.getAt(0) == 'S') && (Msg.getAt(1) == 'R') ) 00404 { 00405 iStatus = (Msg.getAt(7) << 24) | (Msg.getAt(6) << 16) 00406 | (Msg.getAt(5) << 8) | (Msg.getAt(4) ); 00407 00408 bRet = evalStatusRegister(iStatus); 00409 break; 00410 } 00411 00412 if ( iCnt > 300 ) 00413 { 00414 std::cout << "CanDriveHarmonica::enableMotor(): No answer on status request" << std::endl; 00415 bRet = false; 00416 break; 00417 } 00418 00419 usleep(10000); 00420 iCnt++; 00421 } 00422 00423 // ------------------- start watchdog timer 00424 m_WatchdogTime.SetNow(); 00425 m_SendTime.SetNow(); 00426 00427 return bRet; 00428 } 00429 00430 //----------------------------------------------- 00431 bool CanDriveHarmonica::reset() 00432 { 00433 // repeat initialization 00434 00435 // start network 00436 CanMsg msg; 00437 msg.m_iID = 0; 00438 msg.m_iLen = 2; 00439 msg.set(1,0,0,0,0,0,0,0); 00440 m_pCanCtrl->transmitMsg(msg); 00441 00442 // init and start 00443 bool bRet = init(); 00444 bRet |= start(); 00445 00446 return bRet; 00447 } 00448 //----------------------------------------------- 00449 bool CanDriveHarmonica::shutdown() 00450 { 00451 std::cout << "shutdown drive " << m_DriveParam.getDriveIdent() << std::endl; 00452 00453 IntprtSetInt(8, 'M', 'O', 0, 0); 00454 00455 return true; 00456 } 00457 00458 //----------------------------------------------- 00459 bool CanDriveHarmonica::startWatchdog(bool bStarted) 00460 { 00461 if (bStarted == true) 00462 { 00463 //save Watchdog state into member variable 00464 m_bWatchdogActive = true; 00465 // ------- init watchdog 00466 // Harmonica checks PC hearbeat 00467 // note: the COB-ID for a heartbeat message = 0x700 + Device ID 00468 00469 const int c_iHeartbeatTimeMS = 1000; 00470 const int c_iNMTNodeID = 0x00; 00471 00472 // consumer (PC) heartbeat time 00473 sendSDODownload(0x1016, 1, (c_iNMTNodeID << 16) | c_iHeartbeatTimeMS); 00474 00475 // error behavior after failure: 0=pre-operational, 1=no state change, 2=stopped" 00476 sendSDODownload(0x1029, 1, 2); 00477 00478 // motor behavior after heartbeat failre: "quick stop" 00479 sendSDODownload(0x6007, 0, 3); 00480 00481 // acivate emergency events: "heartbeat event" 00482 // Object 0x2F21 = "Emergency Events" which cause an Emergency Message 00483 // Bit 3 is responsible for Heartbeart-Failure.--> Hex 0x08 00484 sendSDODownload(0x2F21, 0, 0x08); 00485 usleep(20000); 00486 00487 } 00488 else 00489 { 00490 //save Watchdog state into member variable 00491 m_bWatchdogActive = false; 00492 00493 //Motor action after Hearbeat-Error: No Action 00494 sendSDODownload(0x6007, 0, 0); 00495 00496 //Error Behavior: No state change 00497 sendSDODownload(0x1029, 1, 1); 00498 00499 // Deacivate emergency events: "heartbeat event" 00500 // Object 0x2F21 = "Emergency Events" which cause an Emergency Message 00501 // Bit 3 is responsible for Heartbeart-Failure. 00502 sendSDODownload(0x2F21, 0, 0x00); 00503 usleep(25000); 00504 00505 00506 } 00507 00508 return true; 00509 } 00510 00511 //----------------------------------------------- 00512 bool CanDriveHarmonica::disableBrake(bool bDisabled) 00513 { 00514 return true; 00515 } 00516 00517 //----------------------------------------------- 00518 double CanDriveHarmonica::getTimeToLastMsg() 00519 { 00520 m_CurrentTime.SetNow(); 00521 00522 return m_CurrentTime - m_WatchdogTime; 00523 } 00524 //----------------------------------------------- 00525 bool CanDriveHarmonica::getStatusLimitSwitch() 00526 { 00527 return m_bLimSwRight; 00528 } 00529 //----------------------------------------------- 00530 bool CanDriveHarmonica::initHoming() 00531 { 00532 const int c_iPosRef = m_DriveParam.getEncOffset(); 00533 00534 // 1. make sure that, if on elmo controller still a pending homing from a previous startup is running (in case of warm-start without switching of the whole robot), this old sequence is disabled 00535 // disarm homing process 00536 IntprtSetInt(8, 'H', 'M', 1, 0); 00537 00538 // always give can and controller some time to understand the command 00539 usleep(20000); 00540 00541 /* THIS is needed for head_axis on cob3-2! 00542 00543 //set input logic to 'general purpose' 00544 IntprtSetInt(8, 'I', 'L', 2, 7); 00545 usleep(20000); 00546 */ 00547 00548 // 2. configure the homing sequence 00549 // 2.a set the value to which the increment counter shall be reseted as soon as the homing event occurs 00550 // value to load at homing event 00551 IntprtSetInt(8, 'H', 'M', 2, c_iPosRef); 00552 usleep(20000); 00553 00554 // 2.b choose the chanel/switch on which the controller listens for a change or defined logic level (the homing event) (high/low/falling/rising) 00555 // home event 00556 // iHomeEvent = 5 : event according to defined FLS switch (for scara arm) 00557 // iHomeEvent = 9 : event according to definded DIN1 switch (for full steerable wheels COb3) 00558 // iHomeEvent =11 : event according to ?? (for COb3 Head-Axis) 00559 IntprtSetInt(8, 'H', 'M', 3, m_DriveParam.getHomingDigIn()); 00560 //IntprtSetInt(8, 'H', 'M', 3, 11); //cob3-2 00561 usleep(20000); 00562 00563 00564 // 2.c choose the action that the controller shall perform after the homing event occured 00565 // HM[4] = 0 : after Event stop immediately 00566 // HM[4] = 2 : Do nothing! 00567 IntprtSetInt(8, 'H', 'M', 4, 2); 00568 usleep(20000); 00569 00570 // 2.d choose the setting of the position counter (i.e. to the value defined in 2.a) after the homing event occured 00571 // HM[5] = 0 : absolute setting of position counter: PX = HM[2] 00572 IntprtSetInt(8, 'H', 'M', 5, 0); 00573 usleep(20000); 00574 00575 // 3. let the motor turn some time to give him the possibility to escape the approximation sensor if accidently in home position already at the beginning of the sequence (done in CanCtrlPltf...) 00576 00577 return true; 00578 } 00579 00580 00581 //----------------------------------------------- 00582 bool CanDriveHarmonica::execHoming() //not used by CanCtrlPltf, that has its own homing implementation 00583 { 00584 00585 int iCnt; 00586 CanMsg Msg; 00587 bool bRet = true; 00588 00589 int iNrDrive = m_DriveParam.getDriveIdent(); 00590 00591 // 4. arm the homing process -> as soon as the approximation sensor is reached and the homing event occurs the commands set in 2. take effect 00592 // arm homing process 00593 IntprtSetInt(8, 'H', 'M', 1, 1); 00594 00595 // 5. clear the can buffer to get rid of all uneccessary and potentially disturbing commands still floating through the wires 00596 do 00597 { 00598 // read from can 00599 bRet = m_pCanCtrl->receiveMsg(&Msg); 00600 } 00601 while(bRet == true); 00602 00603 // 6. now listen for status of homing, to synchronize program flow -> proceed only after homing was succesful (homing disarmed by elmo) or timeout occured 00604 00605 // set timeout counter to zero 00606 iCnt = 0; 00607 00608 do 00609 { 00610 // 6.a ask for status of homing process (armed/disarmed) 00611 // ask for first byte in Homing Configuration 00612 IntprtSetInt(4, 'H', 'M', 1, 0); 00613 00614 // 6.b read message from can 00615 m_pCanCtrl->receiveMsgRetry(&Msg, 10); 00616 00617 // 6.c see if received message is answer of request and if so what is the status 00618 if( (Msg.getAt(0) == 'H') && (Msg.getAt(1) == 'M') ) 00619 { 00620 // status message (homing armed = 1 / disarmed = 0) is encoded in 5th byte 00621 if(Msg.getAt(4) == 0) 00622 { 00623 // if 0 received: elmo disarmed homing after receiving the defined event 00624 std::cout << "Got Homing-Signal " << std::endl; 00625 m_bLimSwRight = true; 00626 break; 00627 } 00628 } 00629 00630 // increase count for timeout 00631 usleep(10000); 00632 iCnt++; 00633 00634 } 00635 while((m_bLimSwRight == false) && (iCnt<2000)); // wait some time 00636 00637 // 7. see why finished (homed or timeout) and log out 00638 if(iCnt>=2000) 00639 { 00640 std::cout << "Homing failed - limit switch " << iNrDrive << " not reached" << std::endl; 00641 bRet = false; 00642 } 00643 else 00644 { 00645 std::cout << "Homing successful - limit switch " << iNrDrive << " ok" << std::endl; 00646 bRet = true; 00647 } 00648 //IntprtSetInt(8, 'I', 'L', 2, 9); //cob3-2 | ----------------------------------------------------------------------------------- 00649 //usleep(20000); 00650 00651 return bRet; 00652 } 00653 //----------------------------------------------- 00654 void CanDriveHarmonica::setGearPosVelRadS(double dPosGearRad, double dVelGearRadS) 00655 { 00656 int iPosEncIncr; 00657 int iVelEncIncrPeriod; 00658 00659 m_DriveParam.PosVelRadToIncr(dPosGearRad, dVelGearRadS, &iPosEncIncr, &iVelEncIncrPeriod); 00660 00661 if(iVelEncIncrPeriod > m_DriveParam.getVelMax()) 00662 { 00663 iVelEncIncrPeriod = (int)m_DriveParam.getVelMax(); 00664 } 00665 00666 if(iVelEncIncrPeriod < -m_DriveParam.getVelMax()) 00667 { 00668 iVelEncIncrPeriod = (int)-m_DriveParam.getVelMax(); 00669 } 00670 00671 if(m_iTypeMotion == MOTIONTYPE_POSCTRL) 00672 { 00673 //new: set VELOCITY for PTP Motion 00674 IntprtSetInt(8, 'S', 'P', 0, iVelEncIncrPeriod); 00675 00676 // Position Relativ ("PR") , because of positioning of driving wheel 00677 // which is not initialized to zero on a specific position 00678 // only when command is for homed steering wheel set absolute 00679 if (m_DriveParam.getIsSteer() == true) 00680 IntprtSetInt(8, 'P', 'A', 0, iPosEncIncr); 00681 else 00682 IntprtSetInt(8, 'P', 'R', 0, iPosEncIncr); 00683 00684 IntprtSetInt(4, 'B', 'G', 0, 0); 00685 00686 } 00687 00688 if(m_iTypeMotion == MOTIONTYPE_VELCTRL) 00689 { 00690 iVelEncIncrPeriod *= m_DriveParam.getSign(); 00691 IntprtSetInt(8, 'J', 'V', 0, iVelEncIncrPeriod); 00692 IntprtSetInt(4, 'B', 'G', 0, 0); 00693 } 00694 00695 // request pos and vel by TPDO1, triggered by SYNC msg 00696 // (to request pos by SDO usesendSDOUpload(0x6064, 0) ) 00697 CanMsg msg; 00698 msg.m_iID = 0x80; 00699 msg.m_iLen = 0; 00700 msg.set(0,0,0,0,0,0,0,0); 00701 m_pCanCtrl->transmitMsg(msg); 00702 } 00703 00704 //----------------------------------------------- 00705 void CanDriveHarmonica::setGearVelRadS(double dVelGearRadS) 00706 { 00707 int iVelEncIncrPeriod; 00708 00709 // calc motor velocity from joint velocity 00710 iVelEncIncrPeriod = m_DriveParam.getSign() * m_DriveParam.VelGearRadSToVelMotIncrPeriod(dVelGearRadS); 00711 00712 if(iVelEncIncrPeriod > m_DriveParam.getVelMax()) 00713 { 00714 std::cout << "SteerVelo asked for " << iVelEncIncrPeriod << " EncIncrements" << std::endl; 00715 iVelEncIncrPeriod = (int)m_DriveParam.getVelMax(); 00716 } 00717 00718 if(iVelEncIncrPeriod < -m_DriveParam.getVelMax()) 00719 { 00720 std::cout << "SteerVelo asked for " << iVelEncIncrPeriod << " EncIncrements" << std::endl; 00721 iVelEncIncrPeriod = -1 * (int)m_DriveParam.getVelMax(); 00722 } 00723 00724 IntprtSetInt(8, 'J', 'V', 0, iVelEncIncrPeriod); 00725 IntprtSetInt(4, 'B', 'G', 0, 0); 00726 00727 // request pos and vel by TPDO1, triggered by SYNC msg 00728 // (to request pos by SDO use sendSDOUpload(0x6064, 0) ) 00729 // sync msg is: iID 0x80 with msg (0,0,0,0,0,0,0,0) 00730 CanMsg msg; 00731 msg.m_iID = 0x80; 00732 msg.m_iLen = 0; 00733 msg.set(0,0,0,0,0,0,0,0); 00734 m_pCanCtrl->transmitMsg(msg); 00735 00736 // send heartbeat to keep watchdog inactive 00737 msg.m_iID = 0x700; 00738 msg.m_iLen = 5; 00739 msg.set(0x00,0,0,0,0,0,0,0); 00740 m_pCanCtrl->transmitMsg(msg); 00741 00742 m_CurrentTime.SetNow(); 00743 double dt = m_CurrentTime - m_SendTime; 00744 if ((dt > 1.0) && m_bWatchdogActive) 00745 { 00746 std::cout << "Time between send velocity of motor " << m_DriveParam.getDriveIdent() 00747 << " is too large: " << dt << " s" << std::endl; 00748 } 00749 m_SendTime.SetNow(); 00750 00751 00752 // request status 00753 m_iCountRequestDiv++; 00754 if (m_iCountRequestDiv > m_Param.iDivForRequestStatus) 00755 { 00756 requestStatus(); 00757 m_iCountRequestDiv = 0; 00758 } 00759 } 00760 00761 //----------------------------------------------- 00762 void CanDriveHarmonica::getGearPosRad(double* dGearPosRad) 00763 { 00764 *dGearPosRad = m_dPosGearMeasRad; 00765 } 00766 00767 //----------------------------------------------- 00768 void CanDriveHarmonica::getGearPosVelRadS(double* pdAngleGearRad, double* pdVelGearRadS) 00769 { 00770 *pdAngleGearRad = m_dPosGearMeasRad; 00771 *pdVelGearRadS = m_dVelGearMeasRadS; 00772 } 00773 00774 //----------------------------------------------- 00775 void CanDriveHarmonica::getGearDeltaPosVelRadS(double* pdAngleGearRad, double* pdVelGearRadS) 00776 { 00777 *pdAngleGearRad = m_dPosGearMeasRad - m_dAngleGearRadMem; 00778 *pdVelGearRadS = m_dVelGearMeasRadS; 00779 m_dAngleGearRadMem = m_dPosGearMeasRad; 00780 } 00781 00782 //----------------------------------------------- 00783 void CanDriveHarmonica::getData(double* pdPosGearRad, double* pdVelGearRadS, 00784 int* piTorqueCtrl, int* piStatusCtrl) 00785 { 00786 *pdPosGearRad = m_dPosGearMeasRad; 00787 *pdVelGearRadS = m_dVelGearMeasRadS; 00788 *piTorqueCtrl = m_iTorqueCtrl; 00789 *piStatusCtrl = m_iStatusCtrl; 00790 } 00791 00792 //----------------------------------------------- 00793 void CanDriveHarmonica::requestPosVel() 00794 { 00795 // request pos and vel by TPDO1, triggered by SYNC msg 00796 CanMsg msg; 00797 msg.m_iID = 0x80; 00798 msg.m_iLen = 0; 00799 msg.set(0,0,0,0,0,0,0,0); 00800 m_pCanCtrl->transmitMsg(msg); 00801 // (to request pos by SDO use sendSDOUpload(0x6064, 0) ) 00802 } 00803 00804 //----------------------------------------------- 00805 void CanDriveHarmonica::sendHeartbeat() 00806 { 00807 CanMsg msg; 00808 msg.m_iID = 0x700; 00809 msg.m_iLen = 5; 00810 msg.set(0x00,0,0,0,0,0,0,0); 00811 m_pCanCtrl->transmitMsg(msg); 00812 } 00813 00814 //----------------------------------------------- 00815 void CanDriveHarmonica::requestStatus() 00816 { 00817 IntprtSetInt(4, 'S', 'R', 0, 0); 00818 } 00819 00820 //----------------------------------------------- 00821 void CanDriveHarmonica::requestMotorTorque() 00822 { 00823 // send command for requesting motor current: 00824 IntprtSetInt(4, 'I', 'Q', 0, 0); // active current 00825 //IntprtSetInt(4, 'I', 'D', 0, 0); // reactive current 00826 } 00827 00828 //----------------------------------------------- 00829 bool CanDriveHarmonica::isError() 00830 { 00831 if (m_iMotorState != ST_MOTOR_FAILURE) 00832 { 00833 // Check timeout of can communication 00834 double dWatchTime = getTimeToLastMsg(); 00835 00836 if (dWatchTime>m_Param.dCanTimeout) 00837 { 00838 if ( m_bOutputOfFailure == false) 00839 { 00840 std::cout << "Motor " << m_DriveParam.getDriveIdent() << 00841 " has no can communication for " << dWatchTime << " s." << std::endl; 00842 } 00843 00844 m_iMotorState = ST_MOTOR_FAILURE; 00845 m_FailureStartTime.SetNow(); 00846 } 00847 00848 } 00849 00850 return (m_iMotorState == ST_MOTOR_FAILURE); 00851 } 00852 //----------------------------------------------- 00853 bool CanDriveHarmonica::setTypeMotion(int iType) 00854 { 00855 int iMaxAcc = int(m_DriveParam.getMaxAcc()); 00856 int iMaxDcc = int(m_DriveParam.getMaxDec()); 00857 CanMsg Msg; 00858 00859 if (iType == MOTIONTYPE_POSCTRL) 00860 { 00861 // 1.) Switch to UnitMode = 5 (Single Loop Position Control) // 00862 00863 // switch off Motor to change Unit-Mode 00864 IntprtSetInt(8, 'M', 'O', 0, 0); 00865 usleep(20000); 00866 // switch Unit-Mode 00867 IntprtSetInt(8, 'U', 'M', 0, 5); 00868 00869 // set Target Radius to X Increments 00870 IntprtSetInt(8, 'T', 'R', 1, 15); 00871 // set Target Time to X ms 00872 IntprtSetInt(8, 'T', 'R', 2, 100); 00873 00874 // set maximum Acceleration to X Incr/s^2 00875 IntprtSetInt(8, 'A', 'C', 0, iMaxAcc); 00876 // set maximum decceleration to X Incr/s^2 00877 IntprtSetInt(8, 'D', 'C', 0, iMaxDcc); 00878 usleep(100000); 00879 00880 00881 } 00882 else if (iType == MOTIONTYPE_TORQUECTRL) 00883 { 00884 // Switch to TorqueControll-Mode 00885 // switch off Motor to change Unit-Mode 00886 IntprtSetInt(8, 'M', 'O', 0, 0); 00887 usleep(50000); 00888 // switch Unit-Mode 1: Torque Controlled 00889 IntprtSetInt(8, 'U', 'M', 0, 1); 00890 // disable external compensation input 00891 // to avoid noise from that input pin 00892 IntprtSetInt(8, 'R', 'M', 0, 0); 00893 00894 // debugging: 00895 std::cout << "Motor"<<m_DriveParam.getDriveIdent()<<" Unit Mode switched to: TORQUE controlled" << std::endl; 00896 usleep(100000); 00897 } 00898 else 00899 { 00900 //Default Motion Type = VelocityControled 00901 // switch off Motor to change Unit-Mode 00902 IntprtSetInt(8, 'M', 'O', 0, 0); 00903 // switch Unit-Mode 00904 IntprtSetInt(8, 'U', 'M', 0, 2); 00905 // set profiler Mode (only if Unit Mode = 2) 00906 IntprtSetInt(8, 'P', 'M', 0, 1); 00907 00908 // set maximum Acceleration to X Incr/s^2 00909 IntprtSetInt(8, 'A', 'C', 0, iMaxAcc); 00910 // set maximum decceleration to X Incr/s^2 00911 IntprtSetInt(8, 'D', 'C', 0, iMaxDcc); 00912 usleep(100000); 00913 } 00914 00915 m_iTypeMotion = iType; 00916 return true; 00917 } 00918 00919 00920 //----------------------------------------------- 00921 void CanDriveHarmonica::IntprtSetInt(int iDataLen, char cCmdChar1, char cCmdChar2, int iIndex, int iData) 00922 { 00923 char cIndex[2]; 00924 char cInt[4]; 00925 CanMsg CMsgTr; 00926 00927 CMsgTr.m_iID = m_ParamCanOpen.iRxPDO2; 00928 CMsgTr.m_iLen = iDataLen; 00929 00930 cIndex[0] = iIndex; 00931 cIndex[1] = (iIndex >> 8) & 0x3F; // The two MSB must be 0. Cf. DSP 301 Implementation guide p. 39. 00932 00933 cInt[0] = iData; 00934 cInt[1] = iData >> 8; 00935 cInt[2] = iData >> 16; 00936 cInt[3] = iData >> 24; 00937 00938 CMsgTr.set(cCmdChar1, cCmdChar2, cIndex[0], cIndex[1], cInt[0], cInt[1], cInt[2], cInt[3]); 00939 m_pCanCtrl->transmitMsg(CMsgTr); 00940 } 00941 00942 //----------------------------------------------- 00943 void CanDriveHarmonica::IntprtSetFloat(int iDataLen, char cCmdChar1, char cCmdChar2, int iIndex, float fData) 00944 { 00945 char cIndex[2]; 00946 char cFloat[4]; 00947 CanMsg CMsgTr; 00948 char* pTempFloat = NULL; 00949 00950 CMsgTr.m_iID = m_ParamCanOpen.iRxPDO2; 00951 CMsgTr.m_iLen = iDataLen; 00952 00953 cIndex[0] = iIndex; 00954 // for sending float values bit 6 has to be zero and bit 7 one (according to Elmo Implementation guide) 00955 cIndex[1] = (iIndex >> 8) & 0x3F; // setting bit 6 to zero with mask 0b10111111->0xBF 00956 cIndex[1] = cIndex[1] | 0x80; // setting bit 7 to one with mask 0b10000000 ->0x80 00957 00958 pTempFloat = (char*)&fData; 00959 for( int i=0; i<4; i++ ) 00960 cFloat[i] = pTempFloat[i]; 00961 00962 CMsgTr.set(cCmdChar1, cCmdChar2, cIndex[0], cIndex[1], cFloat[0], cFloat[1], cFloat[2], cFloat[3]); 00963 m_pCanCtrl->transmitMsg(CMsgTr); 00964 } 00965 00966 //----------------------------------------------- 00967 // SDO Communication Protocol, most functions are used for general SDO Segmented Transfer 00968 //----------------------------------------------- 00969 00970 //----------------------------------------------- 00971 void CanDriveHarmonica::sendSDOAbort(int iObjIndex, int iObjSubIndex, unsigned int iErrorCode) 00972 { 00973 CanMsg CMsgTr; 00974 const int ciAbortTransferReq = 0x04 << 5; 00975 00976 CMsgTr.m_iLen = 8; 00977 CMsgTr.m_iID = m_ParamCanOpen.iRxSDO; 00978 00979 unsigned char cMsg[8]; 00980 00981 cMsg[0] = ciAbortTransferReq; 00982 cMsg[1] = iObjIndex; 00983 cMsg[2] = iObjIndex >> 8; 00984 cMsg[3] = iObjSubIndex; 00985 cMsg[4] = iErrorCode; 00986 cMsg[5] = iErrorCode >> 8; 00987 cMsg[6] = iErrorCode >> 16; 00988 cMsg[7] = iErrorCode >> 24; 00989 00990 CMsgTr.set(cMsg[0], cMsg[1], cMsg[2], cMsg[3], cMsg[4], cMsg[5], cMsg[6], cMsg[7]); 00991 m_pCanCtrl->transmitMsg(CMsgTr); 00992 } 00993 00994 //----------------------------------------------- 00995 void CanDriveHarmonica::receivedSDOTransferAbort(unsigned int iErrorCode){ 00996 std::cout << "SDO Abort Transfer received with error code: " << iErrorCode; 00997 seg_Data.statusFlag = segData::SDO_SEG_FREE; 00998 } 00999 01000 //----------------------------------------------- 01001 void CanDriveHarmonica::sendSDOUpload(int iObjIndex, int iObjSubIndex) 01002 { 01003 CanMsg CMsgTr; 01004 const int ciInitUploadReq = 0x40; 01005 01006 CMsgTr.m_iLen = 8; 01007 CMsgTr.m_iID = m_ParamCanOpen.iRxSDO; 01008 01009 unsigned char cMsg[8]; 01010 01011 cMsg[0] = ciInitUploadReq; 01012 cMsg[1] = iObjIndex; 01013 cMsg[2] = iObjIndex >> 8; 01014 cMsg[3] = iObjSubIndex; 01015 cMsg[4] = 0x00; 01016 cMsg[5] = 0x00; 01017 cMsg[6] = 0x00; 01018 cMsg[7] = 0x00; 01019 01020 CMsgTr.set(cMsg[0], cMsg[1], cMsg[2], cMsg[3], cMsg[4], cMsg[5], cMsg[6], cMsg[7]); 01021 m_pCanCtrl->transmitMsg(CMsgTr); 01022 } 01023 01024 //----------------------------------------------- 01025 void CanDriveHarmonica::sendSDODownload(int iObjIndex, int iObjSubIndex, int iData) 01026 { 01027 CanMsg CMsgTr; 01028 01029 const int ciInitDownloadReq = 0x20; 01030 const int ciNrBytesNoData = 0x00; 01031 const int ciExpedited = 0x02; 01032 const int ciDataSizeInd = 0x01; 01033 01034 CMsgTr.m_iLen = 8; 01035 CMsgTr.m_iID = m_ParamCanOpen.iRxSDO; 01036 01037 unsigned char cMsg[8]; 01038 01039 cMsg[0] = ciInitDownloadReq | (ciNrBytesNoData << 2) | ciExpedited | ciDataSizeInd; 01040 cMsg[1] = iObjIndex; 01041 cMsg[2] = iObjIndex >> 8; 01042 cMsg[3] = iObjSubIndex; 01043 cMsg[4] = iData; 01044 cMsg[5] = iData >> 8; 01045 cMsg[6] = iData >> 16; 01046 cMsg[7] = iData >> 24; 01047 01048 CMsgTr.set(cMsg[0], cMsg[1], cMsg[2], cMsg[3], cMsg[4], cMsg[5], cMsg[6], cMsg[7]); 01049 m_pCanCtrl->transmitMsg(CMsgTr); 01050 } 01051 01052 //----------------------------------------------- 01053 void CanDriveHarmonica::evalSDO(CanMsg& CMsg, int* pIndex, int* pSubindex) 01054 { 01055 *pIndex = (CMsg.getAt(2) << 8) | CMsg.getAt(1); 01056 *pSubindex = CMsg.getAt(3); 01057 } 01058 01059 //----------------------------------------------- 01060 int CanDriveHarmonica::getSDODataInt32(CanMsg& CMsg) 01061 { 01062 int iData = (CMsg.getAt(7) << 24) | (CMsg.getAt(6) << 16) | 01063 (CMsg.getAt(5) << 8) | CMsg.getAt(4); 01064 01065 return iData; 01066 } 01067 01068 //----------------------------------------------- 01069 int CanDriveHarmonica::receivedSDOSegmentedInitiation(CanMsg& msg) { 01070 01071 if(seg_Data.statusFlag == segData::SDO_SEG_FREE || seg_Data.statusFlag == segData::SDO_SEG_WAITING) { //only accept new SDO Segmented Upload if seg_Data is free 01072 seg_Data.resetTransferData(); 01073 seg_Data.statusFlag = segData::SDO_SEG_COLLECTING; 01074 01075 //read out objectIDs 01076 evalSDO(msg, &seg_Data.objectID, &seg_Data.objectSubID); 01077 01078 //data in byte 4 to 7 contain the number of bytes to be uploaded (if Size indicator flag is set) 01079 if( (msg.getAt(0) & 0x01) == 1) { 01080 seg_Data.numTotalBytes = msg.getAt(7) << 24 | msg.getAt(6) << 16 | msg.getAt(5) << 8 | msg.getAt(4); 01081 } else seg_Data.numTotalBytes = 0; 01082 01083 sendSDOUploadSegmentConfirmation(seg_Data.toggleBit); 01084 } 01085 01086 return 0; 01087 01088 } 01089 01090 //----------------------------------------------- 01091 int CanDriveHarmonica::receivedSDODataSegment(CanMsg& msg){ 01092 01093 int numEmptyBytes = 0; 01094 01095 //Read SDO Upload Protocol: 01096 //Byte 0: SSS T NNN C | SSS=Cmd-Specifier, T=ToggleBit, NNN=num of empty bytes, C=Finished 01097 //Byte 1 to 7: Data 01098 01099 if( (msg.getAt(0) & 0x10) != (seg_Data.toggleBit << 4) ) { 01100 std::cout << "Toggle Bit error, send Abort SDO with \"Toggle bit not alternated\" error" << std::endl; 01101 sendSDOAbort(seg_Data.objectID, seg_Data.objectSubID, 0x05030000); //Send SDO Abort with error code Toggle-Bit not alternated 01102 return 1; 01103 } 01104 01105 if( (msg.getAt(0) & 0x01) == 0x00) { //Is finished-bit not set? 01106 seg_Data.statusFlag = segData::SDO_SEG_COLLECTING; 01107 } else { 01108 //std::cout << "SDO Segmented Transfer finished bit found!" << std::endl; 01109 seg_Data.statusFlag = segData::SDO_SEG_PROCESSING; 01110 }; 01111 01112 numEmptyBytes = (msg.getAt(0) >> 1) & 0x07; 01113 //std::cout << "NUM empty bytes in SDO :" << numEmptyBytes << std::endl; 01114 01115 for(int i=1; i<=7-numEmptyBytes; i++) { 01116 seg_Data.data.push_back(msg.getAt(i)); 01117 } 01118 01119 if(seg_Data.statusFlag == segData::SDO_SEG_PROCESSING) { 01120 finishedSDOSegmentedTransfer(); 01121 } else { 01122 seg_Data.toggleBit = !seg_Data.toggleBit; 01123 sendSDOUploadSegmentConfirmation(seg_Data.toggleBit); 01124 } 01125 01126 return 0; 01127 } 01128 01129 //----------------------------------------------- 01130 void CanDriveHarmonica::sendSDOUploadSegmentConfirmation(bool toggleBit) { 01131 01132 CanMsg CMsgTr; 01133 int iConfirmSegment = 0x60; //first three bits must be css = 3 : 011 00000 01134 iConfirmSegment = iConfirmSegment | (toggleBit << 4); //fourth bit is toggle bit: 011T0000 01135 01136 CMsgTr.m_iLen = 8; 01137 CMsgTr.m_iID = m_ParamCanOpen.iRxSDO; 01138 01139 unsigned char cMsg[8]; 01140 01141 cMsg[0] = iConfirmSegment; 01142 cMsg[1] = 0x00; 01143 cMsg[2] = 0x00; 01144 cMsg[3] = 0x00; 01145 cMsg[4] = 0x00; 01146 cMsg[5] = 0x00; 01147 cMsg[6] = 0x00; 01148 cMsg[7] = 0x00; 01149 01150 CMsgTr.set(cMsg[0], cMsg[1], cMsg[2], cMsg[3], cMsg[4], cMsg[5], cMsg[6], cMsg[7]); 01151 m_pCanCtrl->transmitMsg(CMsgTr); 01152 } 01153 01154 //----------------------------------------------- 01155 void CanDriveHarmonica::finishedSDOSegmentedTransfer() { 01156 seg_Data.statusFlag = segData::SDO_SEG_PROCESSING; 01157 01158 if( (seg_Data.data.size() != seg_Data.numTotalBytes) & (seg_Data.numTotalBytes != 0) ) { 01159 std::cout << "WARNING: SDO tranfer finished but number of collected bytes " 01160 << seg_Data.data.size() << " != expected number of bytes: " << seg_Data.numTotalBytes << std::endl; 01161 //abort processing? 01162 } 01163 01164 if(seg_Data.objectID == 0x2030) { 01165 if(ElmoRec->processData(seg_Data) == 0) seg_Data.statusFlag = segData::SDO_SEG_FREE; 01166 } 01167 } 01168 01169 //----------------------------------------------- 01170 double CanDriveHarmonica::estimVel(double dPos) 01171 { 01172 double dVel; 01173 double dt; 01174 01175 m_CurrentTime.SetNow(); 01176 01177 dt = m_CurrentTime - m_VelCalcTime; 01178 01179 dVel = (dPos - m_dOldPos)/dt; 01180 01181 m_dOldPos = dPos; 01182 m_VelCalcTime.SetNow(); 01183 01184 return dVel; 01185 } 01186 //----------------------------------------------- 01187 bool CanDriveHarmonica::evalStatusRegister(int iStatus) 01188 { 01189 bool bNoError; 01190 01191 // --------- Error status 01192 if( isBitSet(iStatus, 0) ) 01193 { 01194 // ------------ Error 01195 if ( m_bOutputOfFailure == false ) 01196 { 01197 std::cout << "Error of drive: " << m_DriveParam.getDriveIdent() << std::endl; 01198 01199 if( (iStatus & 0x0000000E) == 2) 01200 std::cout << "- drive error under voltage" << std::endl; 01201 01202 if( (iStatus & 0x0000000E) == 4) 01203 std::cout << "- drive error over voltage" << std::endl; 01204 01205 if( (iStatus & 0x0000000E) == 10) 01206 std::cout << "- drive error short circuit" << std::endl; 01207 01208 if( (iStatus & 0x0000000E) == 12) 01209 std::cout << "- drive error overheating" << std::endl; 01210 01211 // Request detailed description of failure 01212 IntprtSetInt(4, 'M', 'F', 0, 0); 01213 } 01214 01215 m_iNewMotorState = ST_MOTOR_FAILURE; 01216 01217 bNoError = false; 01218 } 01219 else if ( isBitSet(iStatus, 6) ) 01220 { 01221 // General failure 01222 if ( m_bOutputOfFailure == false ) 01223 { 01224 std::cout << "Motor " << m_DriveParam.getDriveIdent() << " failure latched" << std::endl; 01225 01226 // Request detailed description of failure 01227 IntprtSetInt(4, 'M', 'F', 0, 0); 01228 01229 m_FailureStartTime.SetNow(); 01230 } 01231 m_iNewMotorState = ST_MOTOR_FAILURE; 01232 01233 bNoError = false; 01234 } 01235 else 01236 { 01237 // ---------- No error 01238 bNoError = true; 01239 01240 // Clear flag for failure output only if at least one 01241 // status message without error has been received. 01242 // Printing an error message on recovery is avoided. 01243 m_bOutputOfFailure = false; 01244 01245 // --------- General status bits 01246 // check if Bit 4 (-> Motor is ON) ist set 01247 if( isBitSet(iStatus, 4) ) 01248 { 01249 if (m_iMotorState != ST_OPERATION_ENABLED) 01250 { 01251 std::cout << "Motor " << m_DriveParam.getDriveIdent() << " operation enabled" << std::endl; 01252 m_FailureStartTime.SetNow(); 01253 } 01254 01255 m_iNewMotorState = ST_OPERATION_ENABLED; 01256 } 01257 else 01258 { 01259 if (m_iMotorState != ST_OPERATION_DISABLED) 01260 { 01261 std::cout << "Motor " << m_DriveParam.getDriveIdent() << " operation disabled" << std::endl; 01262 } 01263 01264 m_iNewMotorState = ST_OPERATION_DISABLED; 01265 } 01266 01267 // Current limit 01268 if( isBitSet(iStatus, 13) ) 01269 { 01270 if (m_bCurrentLimitOn == false) 01271 std::cout << "Motor " << m_DriveParam.getDriveIdent() << "current limit on" << std::endl; 01272 01273 m_bCurrentLimitOn = true; 01274 } 01275 else 01276 m_bCurrentLimitOn = false; 01277 } 01278 01279 // Change state 01280 m_iMotorState = m_iNewMotorState; 01281 01282 if (m_iMotorState == ST_MOTOR_FAILURE) 01283 m_bOutputOfFailure = true; 01284 01285 return bNoError; 01286 } 01287 01288 //----------------------------------------------- 01289 void CanDriveHarmonica::evalMotorFailure(int iFailure) 01290 { 01291 01292 std::cout << "Motor " << m_DriveParam.getDriveIdent() << " has a failure: " << iFailure << std::endl; 01293 01294 if( isBitSet(iFailure, 2) ) 01295 { 01296 std::cout << "- feedback loss" << std::endl; 01297 } 01298 01299 if( isBitSet(iFailure, 3) ) 01300 { 01301 std::cout << "- peak current excced" << std::endl; 01302 } 01303 01304 if( isBitSet(iFailure, 7) ) 01305 { 01306 std::cout << "- speed track error" << std::endl; 01307 } 01308 01309 if( isBitSet(iFailure, 8) ) 01310 { 01311 std::cout << "- position track error" << std::endl; 01312 } 01313 01314 if( isBitSet(iFailure, 17) ) 01315 { 01316 std::cout << "- speed limit exceeded" << std::endl; 01317 } 01318 01319 if( isBitSet(iFailure, 21) ) 01320 { 01321 std::cout << "- motor stuck" << std::endl; 01322 } 01323 } 01324 01325 //----------------------------------------------- 01326 void CanDriveHarmonica::setMotorTorque(double dTorqueNm) 01327 { 01328 // convert commanded motor current into amperes 01329 float fMotCurr = m_DriveParam.getSign() * dTorqueNm / m_DriveParam.getCurrToTorque(); 01330 01331 // check for limitations 01332 if (fMotCurr > m_DriveParam.getCurrMax()) 01333 { 01334 fMotCurr = m_DriveParam.getCurrMax(); 01335 std::cout << "Torque command too high: " << fMotCurr << " Nm. Torque has been limitited." << std::endl; 01336 } 01337 if (fMotCurr < -m_DriveParam.getCurrMax()) 01338 { 01339 fMotCurr = -m_DriveParam.getCurrMax(); 01340 std::cout << "Torque command too high: " << fMotCurr << " Nm. Torque has been limitited." << std::endl; 01341 } 01342 01343 // send Command 01344 IntprtSetFloat(8, 'T', 'C', 0, fMotCurr); 01345 01346 // request pos and vel by TPDO1, triggered by SYNC msg 01347 CanMsg msg; 01348 msg.m_iID = 0x80; 01349 msg.m_iLen = 0; 01350 msg.set(0,0,0,0,0,0,0,0); 01351 m_pCanCtrl->transmitMsg(msg); 01352 01353 // send heartbeat to keep watchdog inactive 01354 sendHeartbeat(); 01355 01356 m_CurrentTime.SetNow(); 01357 double dt = m_CurrentTime - m_SendTime; 01358 if (dt > 1.0) 01359 { 01360 std::cout << "Time between send current/torque of motor " << m_DriveParam.getDriveIdent() 01361 << " is too large: " << dt << " s" << std::endl; 01362 } 01363 m_SendTime.SetNow(); 01364 01365 01366 // request status 01367 m_iCountRequestDiv++; 01368 if (m_iCountRequestDiv > m_Param.iDivForRequestStatus) 01369 { 01370 requestStatus(); 01371 m_iCountRequestDiv = 0; 01372 } 01373 01374 } 01375 01376 //----------------------------------------------- 01377 void CanDriveHarmonica::getMotorTorque(double* dTorqueNm) 01378 { 01379 // With motor sign: 01380 *dTorqueNm = m_DriveParam.getSign() * m_dMotorCurr * m_DriveParam.getCurrToTorque(); 01381 01382 } 01383 01384 01385 01386 //---------------- 01387 //---------------- 01388 //Function, that proceeds (Elmo-) recorder readout 01389 01390 //----------------------------------------------- 01391 int CanDriveHarmonica::setRecorder(int iFlag, int iParam, std::string sParam) { 01392 01393 switch(iFlag) { 01394 case 0: //Configure Elmo Recorder for new Record, param = iRecordingGap, which specifies every which time quantum (4*90usec) a new data point is recorded 01395 if(iParam < 1) iParam = 1; 01396 ElmoRec->isInitialized(true); 01397 ElmoRec->configureElmoRecorder(iParam, m_DriveParam.getDriveIdent()); //int startImmediately is default = 1 01398 return 0; 01399 01400 case 1: //Query upload of previous recorded data, data is being proceeded after complete upload, param = recorded ID, filename 01401 if(!ElmoRec->isInitialized(false)) return 1; 01402 01403 if(seg_Data.statusFlag == segData::SDO_SEG_FREE) { 01404 if( (iParam != 1) && (iParam != 2) && (iParam != 10) && (iParam != 16) ) { 01405 iParam = 1; 01406 std::cout << "Changed the Readout object to #1 as your selected object hasn't been recorded!" << std::endl; 01407 } 01408 ElmoRec->setLogFilename(sParam); 01409 seg_Data.statusFlag = segData::SDO_SEG_WAITING; 01410 ElmoRec->readoutRecorderTry(iParam); //as subindex, give the recorded variable 01411 return 0; 01412 } else { 01413 std::cout << "Previous transmission not finished or colected data hasn't been proceeded yet" << std::endl; 01414 return 2; 01415 } 01416 01417 break; 01418 01419 case 2: //request status, still collecting data during ReadOut process? 01420 if(seg_Data.statusFlag == segData::SDO_SEG_COLLECTING) { 01421 //std::cout << "Transmission of data is still in progress" << std::endl; 01422 return 2; 01423 } else if(seg_Data.statusFlag == segData::SDO_SEG_PROCESSING) { 01424 //std::cout << "Transmission of data finished, data not proceeded yet" << std::endl; 01425 return 2; 01426 } else if(seg_Data.statusFlag == segData::SDO_SEG_WAITING) { 01427 //std::cout << "Still waiting for transmission to begin" << std::endl; 01428 return 2; 01429 } else { //finished transmission and finished proceeding 01430 return 0; 01431 } 01432 01433 break; 01434 01435 case 99: //Abort ongoing SDO data Transmission and clear collected data 01436 sendSDOAbort(0x2030, 0x00, 0x08000020); //send general error abort 01437 seg_Data.resetTransferData(); 01438 return 0; 01439 } 01440 01441 return 0; 01442 }