SerRelayBoard.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Neobotix GmbH
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Neobotix nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 
00036 #ifndef SerRelayBoard_INCLUDEDEF_H
00037 #define SerRelayBoard_INCLUDEDEF_H
00038 
00039 //-----------------------------------------------
00040 
00041 
00042 #include <SerialIO.h>
00043 #include <Mutex.h>
00044 #include <StrUtil.h>
00045 #include <DriveParam.h>
00046 #include <CanMsg.h>
00047 #include <CmdRelaisBoard.h>
00048 
00049 
00050 #include <vector>
00051 #include <boost/array.hpp>
00052 
00053 //-----------------------------------------------
00054 
00059 class SerRelayBoard
00060 {
00061 public:
00062         SerRelayBoard();
00063         //SerRelayBoard(int iTypeLCD, std::string pathToConf="../depreciatedConfig/"); //Deprecated
00064         ~SerRelayBoard();
00065 
00066         // Platform - for function description see interface CanCtrlPltfItf (Old Syntax)
00067         bool initPltf();
00068         bool resetPltf();
00069         bool shutdownPltf();
00070         int evalRxBuffer();
00071         bool isComError();
00072         bool isDriveError();
00073         bool isEMStop();
00074         bool isScannerStop();
00075         void readConfig(        int iTypeLCD,std::string pathToConf, std::string sNumComPort,   int hasMotorRight, 
00076                                 int hasMotorLeft, int hasMotorRearRight, int hasMotorRearLeft,
00077                                 int hasIOBoard, int hasUSBoard, int hasRadarBoard, int hasGyroBoard, 
00078                                 double quickfix1, double quickfix2, double quickfix3, double quickfix4, 
00079                                 DriveParam driveParamLeft, DriveParam driveParamRight,
00080                                 DriveParam driveParamRearLeft, DriveParam driveParamRearRight
00081         );
00082         //new Syntax: 
00083         int sendRequest(); //sends collected data and requests response (in the Old version this was done by: setWheelVel() or setWheelPosVel();
00084 
00085         //Care-O-Bots Syntax
00086         bool init();
00087         bool reset();
00088         bool shutdown();
00089         SerRelayBoard(std::string ComPort, int ProtocolVersion = 1);
00090         
00091         
00092         // Drives - for function description see interface CanCtrlPltfItf
00093         int setWheelVel(int iCanIdent, double dVel, bool bQuickStop);
00094         int setWheelPosVel(int iCanIdent, double dPos, double dVel, bool bQuickStop);
00095         void execMotion(int iGroupID) {}
00096         void sendSynch() {}
00097         void sendHeartbeat() {}
00098 
00099         void requestDriveStatus();
00100         int requestMotPosVel(int iCanIdent);
00101         
00107         int getWheelPosVel(     int iCanIdent, double* pdAngWheelRad, double* pdVelWheelRadS);
00108 
00109         int getWheelDltPosVel(  int iCanIdent, double* pdDltAngWheelRad, double* pdVelWheelRadS);
00110 
00111         void getStatus(int iCanIdent, int* piStatus, int* piTempCel);
00112         int disableBrake(int iCanIdent, bool bDisabled);
00113         int execHoming(int CanIdent); // NOT IMPLEMENTED !!!!
00114         
00115         // Relayboard
00116         int getRelayBoardDigIn();
00117         int setRelayBoardDigOut(int iChannel, bool bOn);
00118         int getRelayBoardDigOut();
00119         int getRelayBoardAnalogIn(int* piAnalogIn);
00120         void setEMStop();
00121         void resetEMStop();
00122 
00123         // IOBoard - for function description see interface CanCtrlPltfItf
00124         void requestIOBoardData();
00125         void getIOBoardJoyValNorm(double* pdJoyXNorm, double* pdJoyYNorm);
00126         void getIOBoardJoyValWheelMean(double* pdVelWheelLeftMean, double* pdVelWheelRightMean);
00127         int getIOBoardBattVoltage();
00128         void requestIOBoardDigIn() { }
00129         int getIOBoardDigIn();
00130         int getIOBoardDigOut();
00131         int setIOBoardDigOut(int iChannel, bool bVal);
00132         void requestIOBoardAnalogIn();
00133         int getIOBoardAnalogIn(int* piAnalogIn);
00134         void writeIOBoardLCD(int iLine, int iColumn, const std::string& sText);
00135 
00136         // USBoard - for function description see interface CanCtrlPltfItf
00137         int startUS(int iChannelActive);
00138         int stopUS();   
00139         void requestUSBoardData1To8();
00140         void requestUSBoardData9To16();
00141         int getUSBoardData1To8(int* piUSDistMM);
00142         int getUSBoardData9To16(int* piUSDistMM);
00143         void requestUSBoardAnalogIn();
00144         void getUSBoardAnalogIn(int* piAnalogIn);
00145 
00146         // GyroBoard - for function description see interface CanCtrlPltfItf
00147         void zeroGyro(bool bZeroActive);
00148         void requestGyroBoardData() { } // done by RelayBoard
00149         int getGyroBoardAng(double* pdAngRad, double dAcc[]);
00150         int getGyroBoardAngBoost(double* pdAngRad, boost::array<double, 3u>& dAcc);
00151         int getGyroBoardDltAng(double* pdAng, double dAcc[]);
00152 
00153         // RadarBoard - for function description see interface CanCtrlPltfItf
00154         void requestRadarBoardData();
00155         int getRadarBoardData(double* pdVelMMS);
00156 
00157         // CanClientGeneric - for function description see interface CanCtrlPltfItf
00158         void addGenericCANListeningId(int id);
00159         void removeGenericCANListeningId(int id);
00160         void getGenericCANMessages(std::vector<CANTimedMessage>& pMessages);
00161         void sendGenericCANMessage(CanMsg& message);
00162 
00163         //Logging
00164         void enable_logging();
00165         void disable_logging();
00166         void log_to_file(int direction, unsigned char cMsg[]);
00167 
00168         enum RelBoardReturns
00169         {
00170                 NO_ERROR = 0,
00171                 NOT_INITIALIZED = 1,
00172                 GENERAL_SENDING_ERROR = 2,
00173                 TOO_LESS_BYTES_IN_QUEUE = 3,
00174                 NO_MESSAGES = 4, //for a long time, no message have been received, check com port!
00175                 CHECKSUM_ERROR = 5,
00176                 MSG_CONFIG = 6,
00177                 MSG_DATA = 7
00178         };
00179 
00180         enum RelBoardCmd
00181         {
00182                 CMD_SET_CHARGE_RELAY = 1,
00183                 CMD_RESET_POS_CNT = 2,
00184                 CMD_QUICK_STOP = 4,
00185                 CMD_SET_RELAY1 = 8,
00186                 CMD_SET_RELAY2 = 16,
00187                 CMD_SET_RELAY3 = 32,
00188                 CMD_SET_RELAY4 = 64,
00189                 CMD_SET_RELAY5 = 128,
00190                 CMD_SET_RELAY6 = 256,
00191                 CMD_ZERO_GYRO = 512
00192         };
00193 
00194         enum RelBoardConfig
00195         {
00196                 CONFIG_HAS_IOBOARD = 1,
00197                 CONFIG_HAS_USBOARD = 2,
00198                 CONFIG_HAS_GYROBOARD = 4,
00199                 CONFIG_HAS_RADARBOARD1 = 8,
00200                 CONFIG_HAS_RADARBOARD2 = 16,
00201                 CONFIG_HAS_DRIVES = 32,
00202                 CONFIG_HAS_4_DRIVES = 64
00203 
00204         };
00205 
00209         enum CANNode
00210         {
00211                 CANNODE_IOBOARD = 0,
00212                 CANNODE_MOTORRIGHT = 1,
00213                 CANNODE_MOTORLEFT = 2,
00214                 CANNODE_USBOARD = 3,
00215                 CANNODE_MOTORREARRIGHT = 4,
00216                 CANNODE_MOTORREARLEFT = 5
00217 
00218         };
00219 
00223         enum MotionType
00224         {
00225                 MOTIONTYPE_VELCTRL,
00226                 MOTIONTYPE_POSCTRL
00227         };
00228 
00229         enum TypeLCD
00230         {
00231                 LCD_20CHAR_TEXT,
00232                 LCD_60CHAR_TEXT,
00233                 RELAY_BOARD_1_4,
00234                 RELAY_BOARD_2
00235         };
00236 
00237 protected:
00238         int protocol_version;
00239         std::string m_sNumComPort;
00240 
00241         DriveParam m_DriveParamLeft, m_DriveParamRight, m_DriveParamRearLeft, m_DriveParamRearRight;
00242 
00243         Mutex m_Mutex;
00244 
00245         double m_dLastPosRight;
00246         double m_dLastPosLeft;
00247         unsigned char m_cDebugLeft[4]; 
00248         unsigned char m_cDebugRight[4];
00249         unsigned char m_cTextDisplay[60];
00250 
00251         int m_iNumBytesSend;
00252         int m_iTypeLCD;
00253         
00254         //logging
00255         bool logging;
00256 
00257 
00258         //relayboard 1.4:
00259         int m_iVelCmdMotRearRightEncS;
00260         int m_iVelCmdMotRearLeftEncS;
00261         char m_cSoftEMStop;
00262         char m_cDebugRearRight[4];
00263         int m_iPosMeasMotRearRightEnc;
00264         int m_iVelMeasMotRearRightEncS;
00265         int m_iPosMeasMotRearLeftEnc;
00266         char m_cDebugRearLeft[4];
00267         int m_iVelMeasMotRearLeftEncS;
00268         int m_iMotRearRightStatus;
00269         int m_iMotRearLeftStatus;
00270         double m_dLastPosRearRight;
00271         double m_dLastPosRearLeft;
00272 
00273 
00274         //-----------------------
00275         // send data
00276 
00277         // RelayBoard
00278         int m_iConfigRelayBoard;
00279         int m_iCmdRelayBoard;
00280         
00281         // IOBoard
00282         int m_iIOBoardDigOut;
00283 
00284         // MotCtrlBoards
00285         int m_iVelCmdMotRightEncS;
00286         int m_iVelCmdMotLeftEncS;
00287 
00288         // USBoard
00289         int m_iUSBoardSensorActive;
00290 
00291         //-----------------------
00292         // rec data
00293 
00294         // Relaisboard
00295         int m_iRelBoardStatus;
00296         int m_iChargeCurrent;
00297         int m_iRelBoardBattVoltage;
00298         int m_iRelBoardKeyPad;
00299         int m_iRelBoardIRSensor[4];
00300         int m_iRelBoardTempSensor;
00301         
00302         // IOBoard
00303         int m_iIOBoardBattVoltage;
00304         int m_iIOBoardStatus;
00305         int m_iIOBoardDigIn;
00306         int m_iIOBoardAnalogIn[8];
00307 
00308         // MotCtrlBoards
00309         int m_iMotRightStatus;
00310         int m_iMotLeftStatus;
00311         int m_iPosMeasMotRightEnc;
00312         int m_iVelMeasMotRightEncS;
00313         int m_iPosMeasMotLeftEnc;
00314         int m_iVelMeasMotLeftEncS;
00315 
00316         // GyroBoard
00317         int m_iGyroBoardStatus;
00318         bool m_bGyroBoardZeroGyro;
00319         int m_iGyroBoardAng;
00320         int m_iGyroBoardAcc[3];
00321         
00322         // RadarBoards
00323         int m_iRadarBoardStatus;
00324         int m_iRadarBoardVel[4];
00325 
00326         // USBoard
00327         int m_iUSBoardStatus;
00328         int m_iUSBoardSensorData[16];
00329         int m_iUSBoardAnalogData[4];
00330 
00331         SerialIO m_SerIO;
00332 
00333         bool m_bComInit;
00334 
00335         void readConfiguration();
00336         void sendNetStartCanOpen();
00337 
00338         void txCharArray();
00339         void rxCharArray();
00340 
00357         void convDataToSendMsg(unsigned char cMsg[]);
00358 
00359         void convDataToSendMsgRelayBoard2(unsigned char cMsg[]);
00360         
00364         bool convRecMsgToData(unsigned char cMsg[]);
00365 
00366         bool convRecMsgToDataRelayBoard2(unsigned char cMsg[]);
00367 
00368 private:
00369 
00370         int m_iFoundMotors;
00371         int m_iHomedMotors;
00372         int m_iFoundExtHardware;
00373         int m_iConfigured;
00374         int m_iNumBytesRec;
00375         bool initRelayBoard2(); //configure relayboard 2
00376         int evalRxBufferRelayBoard2();
00377         bool autoSendRequest;
00378         double quickFix[4]; //TODO: quick and dirty odometry fix (rostopic echo /odom)
00379 
00380         //data indicators
00381         int m_ihasRelayData;
00382         int m_ihas_LCD_DATA;
00383         int m_iHasIOBoard;
00384         int m_iHasUSBoard;
00385         int m_iHasSpeakerData; 
00386         int m_iChargeState;
00387 
00388 
00389 };
00390 
00391 
00392 //-----------------------------------------------
00393 #endif


neo_relayboard
Author(s): Jan-Niklas Nieland
autogenerated on Thu Jun 6 2019 21:37:07