RelayBoard_v2.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2016, 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 
00047 
00048 #include <vector>
00049 #include <boost/array.hpp>
00050 
00051 //-----------------------------------------------
00052 
00057 class RelayBoardV2
00058 {
00059 public:
00060         //Constructor
00061         RelayBoardV2();
00062         //Deconstructor
00063         ~RelayBoardV2();
00064 
00065 //------------------------------Initialisation-------------------------------------------------------------------------
00066         int openSerial(const char* device,int baudrate); //TODO
00067         int init(const char* device_name, int iactive_motors, int ihoming_motors, int iext_hardware, long lModulo0, long lModulo1, long lModulo2, long lModulo3, long lModulo4, long lModulo5, long lModulo6, long lModulo7);
00068 
00069         bool shutdownPltf();
00070 //-------------------------------Msg Handling--------------------------------------------------------------------------
00071         int evalRxBuffer();
00072 
00073         int sendDataToRelayBoard();
00074 
00075         int convDataToSendMsg(unsigned char cMsg[]);
00076 
00077         void convRecMsgToData(unsigned char cMsg[]);
00078 //------------------------------Set Data for next Message--------------------------------------------------------------
00079 
00080         //RelayBoard
00081         void startCharging();
00082         void stopCharging();
00083         void setRelayBoardDigOut(int iChannel, bool bOn);       
00084 
00085         //Motors
00086         void setMotorDesiredEncS(int motor_nr, long dVel);
00087         
00088         //EM-Stop
00089         void setEMStop();       
00090         void resetEMStop();
00091 
00092         //LCD
00093         void writeLCD(const std::string& sText);
00094 
00095         //USBoard
00096         void startUSBoard(int iChannelActive);
00097         void stopUSBoard();
00098 
00099         //IOBoard
00100         void setIOBoardDigOut(int iChannel, bool bVal);
00101 //------------------------------Get Data for Topics--------------------------------------------------------------------
00102         //EM-Stop
00103         bool isEMStop();
00104         bool isScannerStop();
00105 
00106         //RelayBoard Data
00107         void getRelayBoardState(int* State);
00108         void getTemperature(int* temp);
00109         void getBattVoltage(int* battvolt);
00110         void getChargingCurrent(int* current);
00111         void getChargingState(int* state);
00112         void getRelayBoardDigOut(int* DigOut);
00113         void getKeyPad(int* keypad);
00114 
00115         //Motors
00116         void getMotorEnc(int imotor_nr,long* lmotorEnc);
00117         void getMotorEncS(int imotor_nr,long* lmotorEncS);
00118         void getMotorState(int imotor_nr,int* lmotorStatus);
00119         
00120         //USBoard
00121         void getUSBoardData1To8(int* piUSDistMM);
00122         void getUSBoardData9To16(int* piUSDistMM);
00123         void getUSBoardAnalogIn(int* piAnalogIn);
00124         
00125         //IOBoard
00126         void getIOBoardDigIn(int* DigIn);
00127         void getIOBoardDigOut(int* DigOut);
00128         void getIOBoardAnalogIn(int* iAnalogIn);
00129 //------------------------------Logging--------------------------------------------------------------------------------
00130         void enable_logging();
00131         void disable_logging();
00132         void log_to_file(int direction, unsigned char cMsg[]);  
00133 
00134         enum RelBoardReturns
00135         {
00136                 NO_ERROR = 0,
00137                 NOT_INITIALIZED = 1,
00138                 GENERAL_SENDING_ERROR = 2,
00139                 TOO_LESS_BYTES_IN_QUEUE = 3,
00140                 NO_MESSAGES = 4, //for a long time, no message have been received, check com port!
00141                 CHECKSUM_ERROR = 5,
00142                 MSG_CONFIG = 6,
00143                 MSG_DATA = 7
00144         };
00145 private:
00146 
00147         SerialIO m_SerIO;
00148 
00149         Mutex m_Mutex;
00150 
00151         //Config Bits
00152         int m_iFoundMotors;
00153         int m_iHomedMotors;
00154         int m_iFoundExtHardware;
00155         int m_iConfigured;
00156         int m_iNumBytesRec;
00157         int m_iNumBytesSend;
00158 
00159         //data indicators
00160         int m_ihasRelayData;
00161         int m_ihas_LCD_DATA;
00162         int m_iHasIOBoard;
00163         int m_iHasUSBoard;
00164         int m_iHasSpeakerData; 
00165         int m_iChargeState;
00166 
00167         struct Motor
00168         {
00169                 int iMotorActive;
00170                 long lEnc;
00171                 long lEncS;
00172                 int iStatus;
00173                 long ldesiredEncS;
00174         };
00175         Motor m_Motor[8];
00176 
00177         struct Send_MSG
00178         {
00179                 int iSoftEM;
00180                 int iCmdRelayBoard;
00181                 char LCD_Txt[20];
00182                 int IOBoard_Cmd;
00183                 int USBoard_Cmd;
00184                 int Speaker;
00185                 int SpeakerLoud;
00186         };
00187         Send_MSG m_S_MSG;       
00188 
00189         struct Recived_MSG
00190         {
00191                 //normal
00192                 int iRelayBoard_Status;
00193                 int iCharging_Current;
00194                 int iCharging_State;
00195                 int iBattery_Voltage;
00196                 int iKey_Pad;
00197                 int iTemp_Sensor;
00198                 
00199                 //IOBoard 
00200                 int iIODig_In;
00201                 int iIOAnalog_In[8];
00202                 int iIOBoard_State;
00203 
00204                 //USBoard
00205                 int iUSSensor_Dist[16];
00206                 int iUSAnalog_In[4];
00207                 int iUSBoard_State;     
00208         };
00209 
00210         Recived_MSG m_REC_MSG;
00211 
00212         bool m_blogging;
00213 };
00214 
00215 
00216 //-----------------------------------------------
00217 #endif


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