LdmrsSopasLayer.hpp
Go to the documentation of this file.
00001 //
00002 // LdmrsSopasLayer.hpp
00003 //
00004 #ifndef LDMRSSOPASLAYER_HPP
00005 #define LDMRSSOPASLAYER_HPP
00006 
00007 #include "../BasicDatatypes.hpp"
00008 #include "../manager.hpp"
00009 #include "../interfaces/tcp.hpp"
00010 #include "SopasBase.hpp"
00011 #include "../datatypes/EvalCase.hpp"
00012 #include "../datatypes/EvalCases.hpp"
00013 #include "../datatypes/EvalCaseResults.hpp"
00014 #include "../datatypes/FieldParameter.hpp"
00015 #include "../datatypes/Fields.hpp"
00016 #include "../datatypes/SensorStateInfo.hpp"
00017 
00018 // Note that this is not a device, but a device helper class
00019 namespace devices
00020 {
00021         
00022 using namespace datatypes;
00023 
00024 // *********************** LDMRSSopasLayer **************************** //
00025 
00026 
00027 class LdmrsSopasLayer: public SopasBase
00028 {
00029 public:
00030         LdmrsSopasLayer(Manager* manager,
00031                                         const UINT8 deviceID,
00032                                         std::string ipAddress,
00033                                         UINT16 portNumber,
00034                                         bool weWantFieldData,
00035                                         bool weWantScanData,
00036                                         bool readOnlyMode);
00037 
00038         virtual ~LdmrsSopasLayer();
00039 
00040         bool init(Tcp::DisconnectFunction function, void* obj); // UINT32 ipAddress, UINT16 portNumber, bool weWantFieldData, bool readOnlyMode, Tcp::DisconnectFunction function);
00041         bool run();
00042 
00043         // commands supported by LD-MRS
00044         bool action_login();
00045         bool action_logout();
00046         bool action_subscribeEvalCaseResults();
00047         bool action_unSubscribeEvalCaseResults();
00048         bool action_subscribeScanData();
00049         bool action_unSubscribeScanData();
00050         bool action_startMeasure();
00051         bool action_stopMeasure();
00052         bool action_readFields();
00053         bool action_readEvalCases();
00054         bool action_readSerialNumber();
00055         bool action_readScanConfig();
00056         bool action_writeField(UINT16 fieldNum, const FieldParameter& para);
00057         bool action_writeEvalCases(const EvalCases& evalCases);
00058         bool action_flashFieldParameters();
00059         bool action_flashMrsParameters();
00060         bool isFieldDataSubscribed() const
00061         {
00062                 return m_fieldEventIsRegistered;
00063         }
00064 
00065 //      SensorStateInfo getSensorStateInfo();
00066 
00067 protected:
00068 
00069         enum ScanFreqEnum
00070         {
00071                 ScanFreq1250 = 0,
00072                 ScanFreq2500 = 1,
00073                 ScanFreq5000 = 2
00074         };
00075 
00076         // ATTENTION: Assignment can be wrong after protocol change (see SRT/VarRep.h)
00077         enum SopasVariableByIndex_LDMRS
00078         {
00079                 index_var_DeviceIdent = 0x00,
00080                 index_var_SOPASVersion = 0x01,
00081                 index_var_LocationName = 0x02,
00082                 index_var_SerialNumber = 0x03,
00083                 index_var_FirmwareVersion = 0x04,
00084                 index_var_Scanning = 0x05,
00085                 index_var_SopasInfo = 0x06,
00086                 index_var_InternalFeedback = 0x07,
00087                 index_var_TestScanFrequency = 0x08,
00088                 index_var_CIDChecksum = 0x09,
00089                 index_var_TestScanActive = 0x0a,
00090                 index_var_ScanDataConfig = 0x0b,
00091                 index_var_AngleDataConfig = 0x0c,
00092                 index_var_LayerEchoConfig = 0x0d,
00093                 index_var_ScanConfig = 0x0e,
00094                 index_var_MeasMode = 0x0f,
00095                 index_var_ApplRange = 0x10,
00096                 index_var_DataOutputRange = 0x11,
00097                 index_var_AutoStartMeasure = 0x12,
00098                 index_var_field000 = 0x003d,
00099                 index_var_field001 = 0x003e,
00100                 index_var_field002 = 0x003f,
00101                 index_var_field003 = 0x0040,
00102                 index_var_field004 = 0x0041,
00103                 index_var_field005 = 0x0042,
00104                 index_var_field006 = 0x0043,
00105                 index_var_field007 = 0x0044,
00106                 index_var_field008 = 0x0045,
00107                 index_var_field009 = 0x0046,
00108                 index_var_field010 = 0x0047,
00109                 index_var_field011 = 0x0048,
00110                 index_var_field012 = 0x0049,
00111                 index_var_field013 = 0x004a,
00112                 index_var_field014 = 0x004b,
00113                 index_var_field015 = 0x004c,
00114                 index_var_numOfParamFields = 0x004d,
00115                 index_var_evalCaseParam = 0x004e
00116         };
00117 
00118         static const UINT16 MAX_NUM_OF_FIELDS = 16;
00119 
00120         // Data taken from generated file S_Methds.c
00121         enum SopasMethodByIndex_LDMRS
00122         {
00123                 index_meth_SetAccessMode = 0x0000,
00124                 index_meth_GetAccessMode = 0x0001,
00125                 index_meth_Run = 0x0002,
00126                 index_meth_FlashFieldParameters = 0x0003,
00127                 index_meth_GetDescription = 0x0004,
00128                 index_meth_CheckPassword = 0x0005,
00129                 index_meth_MthdFlashLUXParameters = 0x0006,
00130                 index_meth_mStartMeasure = 0x000b,
00131                 index_meth_mStopMeasure = 0x000c
00132         };
00133 
00134         enum SopasEventByIndex_LDMRS
00135         {
00136                 index_event_Scanning = 0x0000,
00137                 index_event_ScanDataMonitor = 0x0011,
00138                 index_event_aEvalCaseResult = 0x0029
00139         };
00140 
00141 private:
00142         SensorStateInfo getSensorStateInfo();
00143         
00144         UINT32 colaB_fieldEncoder(BYTE* buffer, const FieldParameter& fieldPara);
00145         FieldParameter* colaB_fieldDecoder(SopasAnswer* answer);
00146         void evalCaseResultDecoder(SopasEventMessage& frame);
00147         void scanDataDecoder(SopasEventMessage& frame);
00148         EvalCases colaB_evalCaseDecoder(SopasAnswer* answer);
00149         UINT32 colaB_evalCaseEncoder(BYTE* buffer, const EvalCases& evalCases);
00150         double angleToRad(INT32 angle);
00151 
00152         Manager* m_manager;
00153         UINT32 m_deviceId;
00154         bool m_beVerbose;
00155 
00156         EvalCaseResults m_lastEvalCaseResults; // needed for ldmrs
00157         EvalCases m_evalCases;
00158         Fields m_fields;
00159 
00160         double m_angleResolution;
00161         double m_scanStartAngle;
00162         double m_scanEndAngle;
00163         double m_scanFreq;
00164         
00165         // Local storage
00166         std::string m_ipAddress;
00167         UINT16 m_portNumber;
00168         bool m_readOnlyMode;
00169 };
00170 
00171 }       // namespace devices
00172 
00173 
00174 #endif // LDMRSSOPASLAYER_HPP


libsick_ldmrs
Author(s): SICK AG , Martin Günther , Jochen Sprickerhof
autogenerated on Wed Jun 14 2017 04:04:50