cplSerial.h
Go to the documentation of this file.
00001 /*
00002  *   Katana Native Interface - A C++ interface to the robot arm Katana.
00003  *   Copyright (C) 2005 Neuronics AG
00004  *   Check out the AUTHORS file for detailed contact information.
00005  *
00006  *   This program is free software; you can redistribute it and/or modify
00007  *   it under the terms of the GNU General Public License as published by
00008  *   the Free Software Foundation; either version 2 of the License, or
00009  *   (at your option) any later version.
00010  *
00011  *   This program is distributed in the hope that it will be useful,
00012  *   but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *   GNU General Public License for more details.
00015  *
00016  *   You should have received a copy of the GNU General Public License
00017  *   along with this program; if not, write to the Free Software
00018  *   Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  */
00020 
00021 
00022 /******************************************************************************************************************/
00023 #ifndef _CPLSERIAL_H_
00024 #define _CPLSERIAL_H_
00025 /******************************************************************************************************************/
00026 #include "common/dllexport.h"
00027 #include "common/exception.h"
00028 #include "KNI/cplBase.h"
00029 #include "KNI/cdlCOMExceptions.h"
00030 
00031 #define NUMBER_OF_RETRIES_SEND  3  // Number of retries after a failing in the Communication
00032 #define NUMBER_OF_RETRIES_RECV  3  // Number of retries after a failing in the Communication
00033 /******************************************************************************************************************/
00034 
00036 const int KATANA_ERROR_FLAG = 192;
00041 
00044 class WrongCRCException : public Exception {
00045 public:
00046         WrongCRCException() throw ():
00047                 Exception("CRC check failed", -20) {}
00048 };
00049 
00052 class FirmwareException : public Exception {
00053 protected:
00054         int _axis_number; 
00055         char _command_char; 
00056 public:
00057         FirmwareException(const std::string & error, const int error_number, const int axis, const char command) throw ():
00058                 Exception("FirmwareException : '" + error + "'", error_number),
00059                 _axis_number(axis),
00060                 _command_char(command) {}
00061         int axis_number() const throw() {
00062             return _axis_number;
00063         }
00064         char command_char() const throw() {
00065             return _command_char;
00066         }
00067 };
00068 
00072 
00075 struct THeader {
00076         byte    size;           
00077         byte    data[256];      
00078 };
00079 
00082 struct TPacket {
00083         byte    send_sz;        
00084         byte    read_sz;        
00085 };
00086 
00087 //----------------------------------------------------------------------------------------------------------------//
00088 
00089 
00092 class DLLDIR CCplSerial : public CCplBase {
00093 
00094 protected:
00095         THeader hdr;                    
00096         TPacket cmd[256];               
00097 
00098         byte    send_buf[256];  
00099         byte    read_buf[256];  
00100 
00101 protected:
00102         virtual bool load_tbl()                                         = 0;    
00103         virtual void defineProtocol(byte _kataddr)      = 0;    
00104 };
00105 
00106 //----------------------------------------------------------------------------------------------------------------//
00107 
00112 // class DLLDIR CCplSerialZero : public CCplSerial {
00113 // 
00114 // protected:
00115 //      virtual bool load_tbl();                                        //!< Loads the command table from the robot's firmware.
00116 //      virtual void defineProtocol(byte _kataddr);     //!< Defines the protocol's attributes.
00117 // 
00118 // public:
00119 //      /*!     \brief  Initializing function
00120 //       *
00121 //       *      Init the protocols basic attributes.
00122 //       */
00123 //      virtual bool init(CCdlBase* _device, byte _kataddr = 24);
00124 // 
00125 // 
00126 //      /*!     \brief  Communication function
00127 //       *
00128 //       *      Sends a communications packet and receives one from the robot.
00129 //       */
00130 //      virtual TRetCOMM comm(const byte* _pack, byte* _buf, byte* _size);
00131 // };
00132 
00133 //----------------------------------------------------------------------------------------------------------------//
00134 
00137 class DLLDIR CCplSerialCRC : public CCplSerial {
00138 
00139 protected:
00140         virtual bool load_tbl();                                        
00141         virtual void defineProtocol(byte _kataddr);     
00142         virtual void send(byte* send_buf, byte write_sz, short retries = 3); // Sends a packet.
00143         virtual void recv(byte* read_buf, byte read_sz, byte* size); // Receives the packet and checks the CRC.
00144 
00145 public:
00150         virtual bool init(CCdlBase* _device, byte _kataddr = 24);
00151 
00156         virtual void comm(const byte* pack, byte* buf, byte* size);
00157 
00162         virtual void getMasterFirmware(short* fw, short* rev);
00163 
00164 };
00165 
00166 /******************************************************************************************************************/
00167 #endif //_CPLSERIALZERO_H_
00168 /******************************************************************************************************************/


kni
Author(s): Martin Günther
autogenerated on Thu Aug 27 2015 13:40:06