Device.h
Go to the documentation of this file.
00001 
00002 /******************************************************************************
00003  * 
00004  * Copyright (c) 2012 
00005  * 
00006  * SCHUNK GmbH & Co. KG
00007  *  
00008  * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 
00009  * 
00010  * Project name: Drivers for "Amtec M5 Protocol" Electronics V4
00011  *                                                                        
00012  * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 
00013  * 
00014  * Email:robotics@schunk.com
00015  * 
00016  * ToDo: 
00017  * 
00018  * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 
00019  * 
00020  * Redistribution and use in source and binary forms, with or without 
00021  * modification, are permitted provided that the following conditions are met: 
00022  * 
00023  *  * Redistributions of source code must retain the above copyright 
00024  *    notice, this list of conditions and the following disclaimer. 
00025  *  * Redistributions in binary form must reproduce the above copyright 
00026  *    notice, this list of conditions and the following disclaimer in the 
00027  *    documentation and/or other materials provided with the distribution. 
00028  *  * Neither the name of SCHUNK GmbH & Co. KG nor the names of its 
00029  *    contributors may be used to endorse or promote products derived from 
00030  *    this software without specific prior written permission. 
00031  * 
00032  * This program is free software: you can redistribute it and/or modify 
00033  * it under the terms of the GNU Lesser General Public License LGPL as 
00034  * published by the Free Software Foundation, either version 3 of the 
00035  * License, or (at your option) any later version. 
00036  * 
00037  * This program is distributed in the hope that it will be useful, 
00038  * but WITHOUT ANY WARRANTY; without even the implied warranty of 
00039  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the 
00040  * GNU Lesser General Public License LGPL for more details. 
00041  * 
00042  * You should have received a copy of the GNU Lesser General Public 
00043  * License LGPL along with this program. 
00044  * If not, see <http://www.gnu.org/licenses/>.
00045  * 
00046  ******************************************************************************/
00047 
00048 
00049 #ifndef CDEVICE_H
00050 #define CDEVICE_H
00051 
00052 #include "../Util/Message.h"
00053 #include "../Util/StopWatch.h"
00054 #include "../ComDef/DeviceErrors.h"
00055 #include "../ComDef/ModuleErrors.h"
00056 #include "../ComDef/IOErrors.h"
00057 #include "../Device/ProtocolCommands.h"
00058 
00059 class CDevice : public CMessage
00060 {
00061         private:
00062 
00063                 // ---- private data ---------------------------------------------------- ;
00064         
00065                 // ---- private auxiliary functions ------------------------------------- ;
00066 
00067         protected:
00068 
00069                 // ---- protected data -------------------------------------------------- ;
00070 
00071                         bool m_bInitFlag;
00072                         char m_acName[128];
00073                         char m_acInitString[128];
00074                         char m_acRevision[20];
00075                         int m_iBaudRate;
00076                         int m_iModuleCount;
00077                         int m_iModuleCountMax;
00078                         std::vector<int> m_aiModuleId;
00079                         std::vector<unsigned short> m_auiModuleVersion;
00080                         CStopWatch m_clTimer;
00081                         int m_iErrorState;
00082 
00083                 // ---- protected auxiliary functions ----------------------------------- ;
00084 
00085                         virtual int reinit(unsigned char ucBaudRateId) = 0;
00086                         virtual int write8Bytes(int iModuleId, bool ack, void* pBytes ) = 0; 
00087                         virtual int getUnsignedLong(int iModuleId, unsigned long* puiData) = 0;
00088 
00089                         virtual int readChar(int iModuleId, int iCommandId, int iParameterId, char* pcData) = 0;
00090                         virtual int readUnsignedChar(int iModuleId, int iCommandId, int iParameterId, unsigned char* pucData) = 0;
00091                         virtual int readShort(int iModuleId, int iCommandId, int iParameterId, short* piData) = 0;
00092                         virtual int readUnsignedShort(int iModuleId, int iCommandId, int iParameterId, unsigned short* puiData) = 0;
00093                         virtual int readLong(int iModuleId, int iCommandId, int iParameterId, long* piData) = 0;
00094                         virtual int readUnsignedLong(int iModuleId, int iCommandId, int iParameterId, unsigned long* puiData) = 0;
00095                         virtual int readFloat(int iModuleId, int iCommandId, int iParameterId, float* pfData) = 0;
00096 
00097                         virtual int readLongUnsignedChars(int iModuleId, int iCommandId, int iParameterId, long* piData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00098                         virtual int readFloatUnsignedChars(int iModuleId, int iCommandId, int iParameterId, float* pfData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00099 
00100                         virtual int writeChar(int iModuleId, int iCommandId, int iParameterId, char cData) = 0;
00101                         virtual int writeUnsignedChar(int iModuleId, int iCommandId, int iParameterId, unsigned char ucData) = 0;
00102                         virtual int writeShort(int iModuleId, int iCommandId, int iParameterId, short iData) = 0;
00103                         virtual int writeUnsignedShort(int iModuleId, int iCommandId, int iParameterId, unsigned short uiData) = 0;
00104                         virtual int writeLong(int iModuleId, int iCommandId, int iParameterId, long iData) = 0;
00105                         virtual int writeUnsignedLong(int iModuleId, int iCommandId, int iParameterId, unsigned long uiData) = 0;
00106                         virtual int writeFloat(int iModuleId, int iCommandId, int iParameterId, float fData) = 0;
00107 
00108                         virtual int writeAll(int iCommandId, int iParameterId) = 0;
00109                         virtual int writeCommand(int iModuleId, int iCommandId) = 0;
00110                         virtual int writeLongShort(int iModuleId, int iCommandId, int iParameterId, long iData, short iTime) = 0;
00111                         virtual int writeFloatShort(int iModuleId, int iCommandId, int iParameterId, float fData, short iTime) = 0;
00112 
00113                         virtual int writeShortReadLongUnsignedChars(int iModuleId, int iCommandId, int iParameterId, short iData, long* piData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00114                         virtual int writeLongReadLongUnsignedChars(int iModuleId, int iCommandId, int iParameterId, long iData, long* piData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00115                         virtual int writeLongShortReadLongUnsignedChars(int iModuleId, int iCommandId, int iParameterId, long iData1, short iData2, long* piData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00116                         virtual int writeFloatReadFloatUnsignedChars(int iModuleId, int iCommandId, int iParameterId, float fData, float* pfData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00117                         virtual int writeFloatShortReadFloatUnsignedChars(int iModuleId, int iCommandId, int iParameterId, float fData, short iData, float* pfData, unsigned char* pucData1, unsigned char* pucData2) = 0;
00118 
00119                         void charStateToLongState(unsigned char uiShort, unsigned long* puiState);
00120 
00121         public:
00122 
00123                 // ---- public data ----------------------------------------------------- ;
00124 
00125         
00126                 // ---- constructors / destructor --------------------------------------- ;
00127 
00129                         CDevice(void);
00131                         CDevice(const CDevice& rclDevice);
00133                         virtual ~CDevice();
00134 
00135                 // ---- operators ------------------------------------------------------- ;
00136                 
00137                         // assignment operator
00138                         CDevice& operator=(const CDevice& rclDevice);
00139 
00140                 // ---- query functions ------------------------------------------------- ;
00141 
00143                         bool getInitFlag();
00145                         const char* getRevision();
00147                         const char* getName();
00149                         const char* getInitString();
00151                         int getBaudRate(void);
00153                         int getModuleCount(void);
00155                         int getModuleIdMap(std::vector<int>& raiModuleId);
00156 
00157                         int getModuleState(int iModuleId, unsigned long* puiState);
00158                         int getModuleType(int iModuleId, unsigned char* pucValue);
00159                         int getModuleVersion(int iModuleId, unsigned short* puiValue);
00160                         int getModuleSerialNo(int iModuleId, unsigned long* puiValue);
00161 
00162                         int getDefConfig(int iModuleId, unsigned long* puiValue);
00163                         int getDefSetup(int iModuleId, unsigned long* puiValue);
00164                         int getDefBaudRate(int iModuleId, unsigned char* pucValue);
00165                         int getDefBurnCount(int iModuleId, unsigned char* pucValue);
00166                         int getDefGearRatio(int iModuleId, float* pfValue);
00167                         int getDefLinearRatio(int iModuleId, float* pfValue);
00168                         int getDefCurOffset(int iModuleId, float* pfValue);
00169                         int getDefCurRatio(int iModuleId, float* pfValue);
00170                         int getDefBrakeTimeOut(int iModuleId, unsigned short* puiValue);
00171                         int getDefIncPerTurn(int iModuleId, unsigned long* puiValue);
00172                         int getDefDioData(int iModuleId, unsigned long* puiValue);
00173                         int getDefA0(int iModuleId, short* piValue);
00174                         int getDefC0(int iModuleId, short* piValue);
00175                         int getDefDamp(int iModuleId, short* piValue);
00176                         int getDefHomeOffset(int iModuleId, float* pfValue);
00177                         int getDefHomeVel(int iModuleId, float* pfValue);
00178                         int getDefMinPos(int iModuleId, float* pfValue);
00179                         int getDefMaxPos(int iModuleId, float* pfValue);
00180                         int getDefMaxVel(int iModuleId, float* pfValue);
00181                         int getDefMaxAcc(int iModuleId, float* pfValue);
00182                         int getDefMaxCur(int iModuleId, float* pfValue);
00183                         int getDefMaxDeltaPos(int iModuleId, float* pfValue);
00184 
00185                         int getConfig(int iModuleId, unsigned long* puiValue);
00186                         int getIncRatio(int iModuleId, float* pValue );
00187                         int getStateDioPos(int iModuleId, unsigned long* puiState, 
00188                                 unsigned char* pucDio, float* pfPos);
00189                         int getDioData(int iModuleId, unsigned long* puiValue);
00190                         int getA0(int iModuleId, short* piValue);
00191                         int getC0(int iModuleId, short* piValue);
00192                         int getDamp(int iModuleId, short* piValue);
00193                         int getHomeOffset(int iModuleId, float* pValue );
00194                         int getHomeOffsetInc(int iModuleId, long* piValue );
00195                         int getHomeVel(int iModuleId, float* pfValue );
00196                         int getHomeVelInc(int iModuleId, long* piValue);
00197                         int getPos(int iModuleId, float* pfPos);
00198                         int getPosInc(int iModuleId, long* piValue);
00199                         int getPosCountInc(int iModuleId, long* piValue);
00200                         int getVel(int iModuleId, float* pfVel);
00201                         int getVelInc(int iModuleId, long* piValue);
00202                         int getIPolVel(int iModuleId, float* pValue );
00203                         int getCur(int iModuleId, float* pfCur);
00204                         int getCurInc(int iModuleId, short* piValue);
00205                         int getMinPos(int iModuleId, float* pfValue);
00206                         int getMinPosInc(int iModuleId, long* piValue);
00207                         int getMaxPos(int iModuleId, float* pfValue);
00208                         int getMaxPosInc(int iModuleId, long* piValue);
00209                         int getMaxVel(int iModuleId, float* pfValue);
00210                         int getMaxVelInc(int iModuleId, long* piValue);
00211                         int getMaxAcc(int iModuleId, float* pfValue);
00212                         int getMaxAccInc(int iModuleId, long* piValue);
00213                         int getMaxCur(int iModuleId, float* pfValue);
00214                         int getDeltaPos(int iModuleId, float* pfValue);
00215                         int getDeltaPosInc(int iModuleId, long* piValue);
00216                         int getMaxDeltaPos(int iModuleId, float* pfValue);
00217                         int getMaxDeltaPosInc(int iModuleId, long* piValue);
00218                         int getSavePos(int iModuleId, float* pfValue);
00219                         int getSyncTime(int iModuleId, short* piValue);
00220                         int getRawMotorCurrent(int iModuleId, short* piValue);
00221                         int getRawMotorSupply(int iModuleId, short* piValue);
00222                         int getRawTemperature(int iModuleId, short* piValue);
00223                         int getRawLogicSupply(int iModuleId, short* piValue);
00224                         int getLoadLimit(int iModuleId, long* piValue);
00225                         int getMaxLoadGradient(int iModuleId, long* piValue);
00226                         int getLoadDeltaTime(int iModuleId, unsigned short* piValue);
00227 
00228                         int getMotorCurrent(int iModuleId, float* pfValue);
00229                         int getMotorSupply(int iModuleId, float* pfValue);
00230                         int getTemperature(int iModuleId, float* pfValue);
00231                         int getLogicSupply(int iModuleId, float* pfValue);
00232 
00233                         int getMinLogicVoltage(int iModuleId, float* pfValue);
00234                         int getMaxLogicVoltage(int iModuleId, float* pfValue);
00235                         int getMinMotorVoltage(int iModuleId, float* pfValue);
00236                         int getMaxMotorVoltage(int iModuleId, float* pfValue);
00237                         int getNominalMotorCurrent(int iModuleId, float* pfValue);
00238                         int getMaximumMotorCurrent(int iModuleId, float* pfValue);
00239                         int getLogicUndershootTime(int iModuleId, long* piValue);
00240                         int getLogicOvershootTime(int iModuleId, long* piValue);
00241                         int getMotorUndershootTime(int iModuleId, long* piValue);
00242                         int getMotorOvershootTime(int iModuleId, long* piValue);
00243                         int getNomCurOvershootTime(int iModuleId, long* piValue);
00244                         int getHMaxCurOvershootTime(int iModuleId, long* piValue);
00245 
00246                         int getDefCANBaudRate(int iModuleId, unsigned char* pucValue);
00247                         int getDefRSBaudRate(int iModuleId, unsigned char* pucValue);
00248 
00249                         int getKpPWMLimit(int iModuleId, long* piValue);
00250                         int getCurrentLimit(int iModuleId, float* pfValue);
00251                         int     getMaxPWMOutput(int iModuleId, long* piValue);
00252 
00253                         virtual int getDataDLR_FTS(std::vector<float>& rafData, long* piState) = 0;
00254                         virtual int getDataSCHUNK_FTC(int iModuleId, int iChannelTypeId, std::vector<float>& rafData, short* piState) = 0;
00255                         virtual int getDataMP55_IO(int iModuleId, float* pfData) = 0;
00256                         virtual int getDataMP55_IO_fast(int iModuleId, float* pfData) = 0;
00257                         virtual int getCanOpenRawAbsEnc(int iModuleId, short* piValue) = 0;
00258 
00259 
00260                 // ---- modify functions ------------------------------------------------ ;
00261 
00263                         void setName(const char* acNameString);
00264                         void setInitString(const char* acInitString);
00265 
00266                         int setConfig(int iModuleId, unsigned long puiValue);
00267                         int setDioData(int iModuleId, unsigned long uiValue);
00268                         int setA0(int iModuleId, short iValue);
00269                         int setC0(int iModuleId, short iValue);
00270                         int setDamp(int iModuleId, short iValue);
00271                         int setHomeOffset(int iModuleId, float fValue );
00272                         int setHomeOffsetInc(int iModuleId, long iValue );
00273                         int setHomeVel(int iModuleId, float fValue);                    
00274                         int setHomeVelInc(int iModuleId, long iValue);
00275                         int setRampVel(int iModuleId, float fValue );
00276                         int setRampAcc(int iModuleId, float fValue );
00277                         int setRampVelInc(int iModuleId, long iValue );
00278                         int setRampAccInc(int iModuleId, long iValue );
00279                         int setMinPos(int iModuleId, float fValue);
00280                         int setMinPosInc(int iModuleId, long iValue);
00281                         int setMaxPos(int iModuleId, float fValue);
00282                         int setMaxPosInc(int iModuleId, long iValue);
00283                         int setMaxVel(int iModuleId, float fValue);
00284                         int setMaxVelInc(int iModuleId, long iValue);
00285                         int setMaxAcc(int iModuleId, float fValue);
00286                         int setMaxAccInc(int iModuleId, long iValue);
00287                         int setMaxCur(int iModuleId, float fValue);
00288                         int setMaxDeltaPos(int iModuleId, float fValue);
00289                         int setMaxDeltaPosInc(int iModuleId, long iValue);
00290                         int setSyncTime(int iModuleId, short iValue);
00291                         int setLoadLimit(int iModuleId, long iValue);
00292                         int setMaxLoadGradient(int iModuleId, long iValue);
00293                         int setLoadDeltaTime(int iModuleId, unsigned short iValue);
00294                         
00295                         int setDefGearRatio(int iModuleId, float fValue);
00296                         int setDefLinRatio(int iModuleId, float fValue);
00297                         int setDefCurRatio(int iModuleId, float fValue);
00298                         int setDefHomeAcc(int iModuleId, float fValue);
00299                         int setModuleSerialNo(int iModuleId, unsigned long uiValue);
00300                         int setDefIncPerTurn(int iModuleId, unsigned long uiValue);
00301                         int setDefBrakeTimeOut(int iModuleId, unsigned short uiValue);
00302                         int setDefAddress(int iModuleId, unsigned char uiValue);
00303                         int setDefCANBaudRate(int iModuleId, unsigned char uiValue);
00304                         int setDefRSBaudRate(int iModuleId, unsigned char uiValue);
00305                         int setDefSetup(int iModuleId, unsigned long uiValue);
00306 
00307                         int setMinLogicVoltage(int iModuleId, float fValue);
00308                         int setMaxLogicVoltage(int iModuleId, float fValue);
00309                         int setMinMotorVoltage(int iModuleId, float fValue);
00310                         int setMaxMotorVoltage(int iModuleId, float fValue);
00311                         int setNominalMotorCurrent(int iModuleId, float fValue);
00312                         int setMaximumMotorCurrent(int iModuleId, float fValue);
00313                         int setLogicUndershootTime(int iModuleId, long iValue);
00314                         int setLogicOvershootTime(int iModuleId, long iValue);
00315                         int setMotorUndershootTime(int iModuleId, long iValue);
00316                         int setMotorOvershootTime(int iModuleId, long iValue);
00317                         int setNomCurOvershootTime(int iModuleId, long iValue);
00318                         int setHMaxCurOvershootTime(int iModuleId, long iValue);
00319 
00320                         int setKpPWMLimit(int iModuleId, long iValue);
00321                         int setCurrentLimit(int iModuleId, float fValue);
00322 
00323                         virtual int setNullSCHUNK_FTC(int iModuleId, short* piState) = 0;
00324                         virtual int setTaraMP55_IO(int iModuleId, float fTara) = 0;
00325                         virtual int setInitMP55_IO_fast(int iModuleId) = 0;
00326 
00327                 // ---- I/O functions --------------------------------------------------- ;
00328 
00329                 // ---- exec functions -------------------------------------------------- ;
00330 
00331                         virtual int init() = 0;
00332                         virtual int init(const char* acInitString) = 0;
00333                         virtual int exit() = 0;
00334 
00335                         virtual int initDLR_FTS() = 0;
00336                         int updateModuleIdMap();
00337 
00338                         int homeModule(int iModuleId);
00339                         int resetModule(int iModuleId);
00340                         int haltModule(int iModuleId);
00341                         int recalcPIDParams(int iModuleId);
00342                         int saveParameters(int iModuleId);
00343 
00344                         int movePos(int iModuleId, float fPos);
00345                         int movePosInc(int iModuleId, long iPos);
00346                         int movePosExtended(int iModuleId, float fPos, 
00347                                 unsigned long* puiState, unsigned char* pucDio, float* pfPos);
00348                         int moveRamp(int iModuleId, float fPos, float fVel, float fAcc);
00349                         int moveRampInc(int iModuleId, long iPos, long iVel, long iAcc);
00350                         int moveRampExtended(int iModuleId, float fPos, float fVel, float fAcc, 
00351                                 unsigned long* puiState, unsigned char* pucDio, float* pfPos);
00352                         int moveVel(int iModuleId, float fVel);
00353                         int moveVelInc(int iModuleId, long iVel);
00354                         int moveVelExtended(int iModuleId, float fCur, 
00355                                 unsigned long* puiState, unsigned char* pucDio, float* pfPos);
00356                         int moveCur(int iModuleId, float fCur);
00357                         int moveCurInc(int iModuleId, long iCur);
00358                         int moveCurExtended(int iModuleId, float fCur, 
00359                                 unsigned long* puiState, unsigned char* pucDio, float* pfPos);
00360                         int moveStep(int iModuleId, float fPos, unsigned short uiTime);
00361                         int moveStepInc(int iModuleId, long iPos, unsigned short uiTime);
00362                         int moveStepExtended(int iModuleId, float fPos, unsigned short uiTime, 
00363                                 unsigned long* puiState, unsigned char* pucDio, float* pfPos);
00364 
00365                 // ---- wait functions -------------------------------------------------- ;
00366 
00367                         int waitForHomeEnd(int iModuleId, unsigned long uiTimeOut = 60000);
00368                         int waitForMotionEnd(int iModuleId, unsigned long uiTimeOut = 60000);
00369                         int waitForRampEnd(int iModuleId, unsigned long uiTimeOut = 60000);
00370                         int waitForRampDec(int iModuleId, unsigned long uiTimeOut = 60000);
00371                         int waitForRampSteady(int iModuleId, unsigned long uiTimeOut = 60000);
00372                         int waitForHomeEndAll(unsigned long uiTimeOut = 60000);
00373                         int waitForMotionEndAll(unsigned long uiTimeOut = 60000);
00374                         int waitForRampEndAll(unsigned long uiTimeOut = 60000);
00375                         virtual int waitForStartMotionAll();
00376 
00377                 // ---- broadcast functions -------------------------------------------------- ;
00378 
00379                         int homeAll(void);
00380                         int resetAll(void);
00381                         int haltAll(void);
00382                         int serveWatchdogAll(void);
00383                         int setBaudRateAll(unsigned char ucBaudRateId);
00384                         int startMotionAll(void);
00385                         int savePosAll(void);
00386 
00387                 // ---- Special functions -------------------------------------------------- ;
00388 
00389                         int xmit8Bytes(int iModuleId, void* pBytes );
00390                         int xack8Bytes(int iModuleId, void* pBytes );
00391                         int doInternal(int iModuleId, void* pBytes );
00392                         int getStateInternal(int iModuleId, unsigned long* pBytes );
00393 
00394 };
00395 
00396 CDevice* newDevice(const char* acInitString);
00397 
00398 #endif


schunk_libm5api
Author(s): Florian Weisshardt
autogenerated on Thu Aug 27 2015 15:06:52