cp1616_io_device.h
Go to the documentation of this file.
00001 /*********************************************************************************************/
00021 #ifndef CP1616_IO_DEVICE_H
00022 #define CP1616_IO_DEVICE_H
00023 
00024 //CP 1616 Annotations
00025 #define ANNOT_NAME       "StarterKit"      // device type (String 25) 
00026 #define ANNOT_ORDERID    "6GK1 161-6AA00"  // Order Id    (String 20) 
00027 #define ANNOT_HW_REV     0                 // HwRevision  (short)     
00028 #define ANNOT_SW_PREFIX  'V'               // SwRevisionPrefix (char) 
00029 #define ANNOT_SW_REV_1   2                 // SwRevision1 (short)     
00030 #define ANNOT_SW_REV_2   6                 // SwRevision2 (short)     
00031 #define ANNOT_SW_REV_3   0                 // SwRevision3 (short)     
00032 
00033 //Known Diagnose alarms for this device
00034 #define CH_ERR_INVAL_LINKUP     0x0100
00035 #define CH_ERR_INVAL_LINKDOWN   0x0101
00036 #define CH_ERR_NO_REDUND_PS     0x0200
00037 #define CH_ERR_NO_CPLUG         0x0201
00038 #define CH_ERR_CPLUG_ERROR      0x0202
00039 
00040 //Values for PNIO_device_open
00041 #define NUMOF_SLOTS             2          // DAP module + 1 slot
00042 #define NUMOF_SUBSLOTS          2         // Number of subslots 
00043 #define NUMOF_BYTES_PER_SUBSLOT 256       // Maximum data length as configured in the sample 
00044 #define VENDOR_ID    0x002a
00045 #define DEVICE_ID    0x0003
00046 #define INSTANCE_ID  0x0001
00047 
00048 #define DEVICE_DATA_ENTRIES     2          // The total number of members of DEVICE_DATA structure  
00049 
00050 #include <ros/ros.h>
00051 
00052 //IO Base headers
00053 #include "pniobase.h"
00054 #include "pniousrd.h"
00055 #include "pnioerrx.h"
00056 
00057 namespace cp1616
00058 {
00059 
00064 struct DeviceData
00065 {
00066   unsigned int slot;
00067   unsigned int subslot;
00068   PNIO_UINT32 modId;
00069   PNIO_UINT32 subslotId;
00070   PNIO_UINT32 api;
00071   PNIO_UINT16 maxSubslots;
00072   int modState;
00073   int subState;
00074   int dir;
00075 };
00076 
00081 class Cp1616IODevice
00082 {
00083 public:
00087   static Cp1616IODevice* getDeviceInstance();
00088 
00092   ~Cp1616IODevice();
00093 
00099   int init();
00100 
00106   int uinit();
00107 
00111   void configureDeviceData();
00112 
00118   int addApi();
00119 
00125   int removeApi();
00126 
00132   int addModSubMod();
00133 
00139   int removeModSubMod();
00140 
00146   int startOperation();
00147 
00153   int stopOperation();
00154 
00160   int updateCyclicOutputData();
00161 
00167   int updateCyclicInputData();
00168 
00176   int doAfterPrmEndIndCbf();
00177 
00184   int doAfterIndataIndCbf();
00185 
00189   DeviceData *p_device_data_;
00190 
00194   std::vector<std::vector <std::vector<PNIO_UINT8> > > input_data_;
00195          
00199   std::vector<std::vector<std::vector<PNIO_UINT8> > > output_data_;
00200   
00202   void setArInfoIndFlag(int value);
00203   void setPrmEndIndFlag(int value);
00204   void setIndataIndFlag(int value);
00205   void setOfflineIndFlag(int value);
00206   void setCpSessionKey(PNIO_UINT16 value);
00207   void setCpArNumber(PNIO_UINT16 value);
00208   void setInputDataLength(int slot_number, int subslot_number, PNIO_UINT32 value);   
00209   void setOutputDataLength(int slot_number, int subslot_number, PNIO_UINT32 value);
00210   void setInputDataIocs(int slot_number, int subslot_number, PNIO_IOXS status);   
00211   void setOutputDataIocs(int slot_number, int subslot_number, PNIO_IOXS status);  
00212   void setInputDataIops(int slot_number, int subslot_number, PNIO_IOXS status);   
00213   void setOutputDataIops(int slot_number, int subslot_number, PNIO_IOXS status);    
00214   
00215   int getArInfoIndFlag();
00216   int getPrmEndIndFlag();
00217   int getIndataIndFlag();
00218   int  getOfflineIndFlag();
00219   PNIO_UINT16 getCpSessionKey();
00220   PNIO_UINT16 getCpArNumber();
00221   PNIO_UINT32 getInputDataLength(int slot_number, int subslot_number);   
00222   PNIO_UINT32 getOutputDataLength(int slot_number, int subslot_number);  
00223   PNIO_IOXS getInputDataIocs(int slot_number, int subslot_number);   
00224   PNIO_IOXS getOutputDataIocs(int slot_number, int subslot_number); 
00225   PNIO_IOXS getInputDataIops(int slot_number, int subslot_number); 
00226   PNIO_IOXS getOutputDataIops(int slot_number, int subslot_number);   
00227   int GetSubmodNum(PNIO_UINT32 mod, PNIO_UINT32 sub);
00228   
00229 private:
00230   
00231   Cp1616IODevice();
00232   static Cp1616IODevice *device_instance_;
00233   
00234   PNIO_UINT32 cp_handle_;
00235   PNIO_UINT32 cp_id_;
00236   unsigned int cp_number_of_slots_;
00237   unsigned int cp_max_number_of_subslots_;
00238 
00239   std::vector<std::vector<PNIO_UINT32> > input_data_length_;
00240   std::vector<std::vector<PNIO_IOXS> >   input_data_iocs_;
00241   std::vector<std::vector<PNIO_IOXS> >   input_data_iops_;
00242          
00243   std::vector<std::vector<PNIO_UINT32> > output_data_length_;
00244   std::vector<std::vector<PNIO_IOXS> >   output_data_iocs_;
00245   std::vector<std::vector<PNIO_IOXS> >   output_data_iops_;
00246                  
00247   int ar_info_ind_flag_;
00248   int prm_end_ind_flag_;
00249   int indata_ind_flag_;
00250   int offline_ind_flag_;
00251   PNIO_UINT16 cp_session_key_;
00252   PNIO_UINT16 cp_ar_number_;
00253 
00254   int idx_table_[DEVICE_DATA_ENTRIES];
00255   
00256   static const int WAIT_FOR_CALLBACK_PERIOD = 100000;
00257   static const int MAX_PRM_END_COUNT = 500;
00258   static const int MAX_INDATA_IND_COUNT = 500;
00259   static const int MAX_OFFLINE_IND_COUNT = 100; 
00260          
00261 }; //cp1616_io_device class
00262 }  //cp1616
00263 
00264 
00265 #endif //CP1616_IO_DEVICE_H


cp1616
Author(s):
autogenerated on Fri Aug 28 2015 13:08:36