CanCtrlPltfCOb3.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef CANCTRLPLTFCOB3_INCLUDEDEF_H
00019 #define CANCTRLPLTFCOB3_INCLUDEDEF_H
00020 
00021 //-----------------------------------------------
00022 
00023 // general includes
00024 
00025 // Headers provided by other cob-packages
00026 #include <cob_canopen_motor/CanDriveItf.h>
00027 #include <cob_canopen_motor/CanDriveHarmonica.h>
00028 #include <cob_generic_can/CanItf.h>
00029 
00030 // Headers provided by cob-packages which should be avoided/removed
00031 #include <cob_utilities/IniFile.h>
00032 #include <cob_utilities/Mutex.h>
00033 
00034 // remove (not supported)
00035 //#include "stdafx.h"
00036 
00037 
00038 //-----------------------------------------------
00039 
00043 class CanCtrlPltfCOb3 // : public CanCtrlPltfItf
00044 {
00045 public:
00046 
00047         //--------------------------------- Basic procedures
00048 
00052         CanCtrlPltfCOb3(std::string iniDirectory);
00053 
00057         ~CanCtrlPltfCOb3();
00058 
00059 
00060         //--------------------------------- Hardware Specification
00061 
00066         enum MotorCANNode
00067         {
00068                 CANNODE_WHEEL1DRIVEMOTOR,
00069                 CANNODE_WHEEL1STEERMOTOR,
00070                 CANNODE_WHEEL2DRIVEMOTOR,
00071                 CANNODE_WHEEL2STEERMOTOR,
00072                 CANNODE_WHEEL3DRIVEMOTOR,
00073                 CANNODE_WHEEL3STEERMOTOR,
00074                 CANNODE_WHEEL4DRIVEMOTOR,
00075                 CANNODE_WHEEL4STEERMOTOR
00076         };
00077 
00078 
00079         //--------------------------------- Commands for all nodes on the bus
00080 
00086         bool initPltf();
00087 
00092         bool resetPltf();
00093 
00098         bool isPltfError();
00099 
00104         bool shutdownPltf();
00105 
00109         bool startWatchdog(bool bStarted);
00110 
00114         int evalCanBuffer();
00115 
00116 
00117         //--------------------------------- Commands specific for motor controller nodes
00118 
00125         int setVelGearRadS(int iCanIdent, double dVelGearRadS);
00126 
00133         void setMotorTorque(int iCanIdent, double dTorqueNm);
00134 
00141         void requestDriveStatus();
00142 
00150         int requestMotPosVel(int iCanIdent);
00151 
00156         void requestMotorTorque();
00157 
00164         int getGearPosVelRadS(int iCanIdent, double* pdAngleGearRad, double* pdVelGearRadS);
00165 
00172         int getGearDeltaPosVelRadS(int iCanIdent, double* pdDeltaAngleGearRad, double* pdVelGearRadS);
00173 
00179         void getStatus(int iCanIdent, int* piStatus, int* piTempCel);
00180 
00186         void getMotorTorque(int iCanIdent, double* pdTorqueNm);
00187 
00188 
00189 
00190         //--------------------------------- Commands specific for a certain motor controller
00191         // have to be implemented here, to keep the CanDriveItf generic
00192 
00203         int ElmoRecordings(int iFlag, int iParam, std::string sString);
00204 
00205         //--------------------------------- Commands for other nodes
00206 
00207 
00208 
00209 
00210 protected:
00211 
00212         //--------------------------------- internal functions
00213 
00218         std::string sIniDirectory;
00219         std::string sComposed;
00220         void readConfiguration();
00221 
00225         void sendNetStartCanOpen();
00226 
00227 
00228         //--------------------------------- Types
00229 
00233         struct ParamType
00234         {
00235                 // Platform config
00236 
00237                 int iHasWheel1DriveMotor;
00238                 int iHasWheel1SteerMotor;
00239                 int iHasWheel2DriveMotor;
00240                 int iHasWheel2SteerMotor;
00241                 int iHasWheel3DriveMotor;
00242                 int iHasWheel3SteerMotor;
00243                 int iHasWheel4DriveMotor;
00244                 int iHasWheel4SteerMotor;
00245 
00246                 double dWheel1SteerDriveCoupling;
00247                 double dWheel2SteerDriveCoupling;
00248                 double dWheel3SteerDriveCoupling;
00249                 double dWheel4SteerDriveCoupling;
00250 
00251                 double dHomeVeloRadS;
00252 
00253                 int iRadiusWheelMM;
00254                 int iDistSteerAxisToDriveWheelMM;
00255 
00256                 int iHasRelayBoard;
00257                 int iHasIOBoard;
00258                 int iHasUSBoard;
00259                 int iHasGyroBoard;
00260                 int iHasRadarBoard;
00261 
00262                 double dCanTimeout;
00263         };
00264 
00268         struct GearMotorParamType
00269         {
00270                 int             iEncIncrPerRevMot;
00271                 double  dVelMeasFrqHz;
00272                 double  dGearRatio;
00273                 double  dBeltRatio;
00274                 int             iSign;
00275                 double  dVelMaxEncIncrS;
00276                 double  dAccIncrS2;
00277                 double  dDecIncrS2;
00278                 double  dScaleToMM;
00279                 int     iEncOffsetIncr;
00280                 bool    bIsSteer;
00281                 double  dCurrentToTorque;
00282                 double  dCurrMax;
00283                 int     iHomingDigIn;
00284         };
00285 
00289         struct CanNeoIDType
00290         {
00291                 int IOBoard_rx_ID;
00292                 int IOBoard_tx_ID;
00293 
00294                 int DriveNeo_W1Drive_rx_ID;
00295                 int DriveNeo_W1Drive_tx_ID;
00296                 int DriveNeo_W1Steer_rx_ID;
00297                 int DriveNeo_W1Steer_tx_ID;
00298 
00299                 int DriveNeo_W2Drive_rx_ID;
00300                 int DriveNeo_W2Drive_tx_ID;
00301                 int DriveNeo_W2Steer_rx_ID;
00302                 int DriveNeo_W2Steer_tx_ID;
00303 
00304                 int DriveNeo_W3Drive_rx_ID;
00305                 int DriveNeo_W3Drive_tx_ID;
00306                 int DriveNeo_W3Steer_rx_ID;
00307                 int DriveNeo_W3Steer_tx_ID;
00308 
00309                 int DriveNeo_W4Drive_rx_ID;
00310                 int DriveNeo_W4Drive_tx_ID;
00311                 int DriveNeo_W4Steer_rx_ID;
00312                 int DriveNeo_W4Steer_tx_ID;
00313 
00314                 int USBoard_rx_ID;
00315                 int USBoard_tx_ID;
00316                 int GyroBoard_rx_ID;
00317                 int GyroBoard_tx_ID;
00318                 int RadarBoard_rx_ID;
00319                 int RadarBoard_tx_ID;
00320         };
00321 
00326         struct CanOpenIDType
00327         {
00328                 // Wheel 1
00329                 // can adresse motor 1
00330                 int TxPDO1_W1Drive;
00331                 int TxPDO2_W1Drive;
00332                 int RxPDO2_W1Drive;
00333                 int TxSDO_W1Drive;
00334                 int RxSDO_W1Drive;
00335                 // can adresse motor 2
00336                 int TxPDO1_W1Steer;
00337                 int TxPDO2_W1Steer;
00338                 int RxPDO2_W1Steer;
00339                 int TxSDO_W1Steer;
00340                 int RxSDO_W1Steer;
00341 
00342                 // Wheel 2
00343                 // can adresse motor 7
00344                 int TxPDO1_W2Drive;
00345                 int TxPDO2_W2Drive;
00346                 int RxPDO2_W2Drive;
00347                 int TxSDO_W2Drive;
00348                 int RxSDO_W2Drive;
00349                 // can adresse motor 8
00350                 int TxPDO1_W2Steer;
00351                 int TxPDO2_W2Steer;
00352                 int RxPDO2_W2Steer;
00353                 int TxSDO_W2Steer;
00354                 int RxSDO_W2Steer;
00355 
00356                 // Wheel 3
00357                 // can adresse motor 5
00358                 int TxPDO1_W3Drive;
00359                 int TxPDO2_W3Drive;
00360                 int RxPDO2_W3Drive;
00361                 int TxSDO_W3Drive;
00362                 int RxSDO_W3Drive;
00363                 // can adresse motor 6
00364                 int TxPDO1_W3Steer;
00365                 int TxPDO2_W3Steer;
00366                 int RxPDO2_W3Steer;
00367                 int TxSDO_W3Steer;
00368                 int RxSDO_W3Steer;
00369 
00370                 // Wheel 4
00371                 // can adresse motor 3
00372                 int TxPDO1_W4Drive;
00373                 int TxPDO2_W4Drive;
00374                 int RxPDO2_W4Drive;
00375                 int TxSDO_W4Drive;
00376                 int RxSDO_W4Drive;
00377                 // can adresse motor 4
00378                 int TxPDO1_W4Steer;
00379                 int TxPDO2_W4Steer;
00380                 int RxPDO2_W4Steer;
00381                 int TxSDO_W4Steer;
00382                 int RxSDO_W4Steer;
00383         };
00384 
00385         //--------------------------------- Parameter
00386         ParamType m_Param;
00387 //      CanNeoIDType m_CanNeoIDParam;
00388         CanOpenIDType m_CanOpenIDParam;
00389 
00390         // Prms for all Motor/Gear combos
00391         GearMotorParamType m_GearMotDrive1;
00392         GearMotorParamType m_GearMotDrive2;
00393         GearMotorParamType m_GearMotDrive3;
00394         GearMotorParamType m_GearMotDrive4;
00395         GearMotorParamType m_GearMotSteer1;
00396         GearMotorParamType m_GearMotSteer2;
00397         GearMotorParamType m_GearMotSteer3;
00398         GearMotorParamType m_GearMotSteer4;
00399 
00400         //--------------------------------- Variables
00401         CanMsg m_CanMsgRec;
00402         Mutex m_Mutex;
00403         bool m_bWatchdogErr;
00404 
00405         //--------------------------------- Components
00406         // Can-Interface
00407         CanItf* m_pCanCtrl;
00408         IniFile m_IniFile;
00409 
00410         int m_iNumMotors;
00411         int m_iNumDrives;
00412 
00413         // Motor-Controllers
00414 /*      CanDriveItf* m_pW1DriveMotor;
00415         CanDriveItf* m_pW1SteerMotor;
00416         CanDriveItf* m_pW2DriveMotor;
00417         CanDriveItf* m_pW2SteerMotor;
00418         CanDriveItf* m_pW3DriveMotor;
00419         CanDriveItf* m_pW3SteerMotor;
00420         CanDriveItf* m_pW4DriveMotor;
00421         CanDriveItf* m_pW4SteerMotor;*/
00422         // pointer to each motors Can-Itf
00423         std::vector<CanDriveItf*> m_vpMotor;
00424         // vector with enums (specifying hardware-structure) -> simplifies cmd-check
00425         // this has to be adapted in c++ file to your hardware
00426         std::vector<int> m_viMotorID;
00427 
00428         // other
00429 
00430 
00431 };
00432 
00433 
00434 //-----------------------------------------------
00435 #endif


cob_base_drive_chain
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:29