Program Listing for File SopasBase.hpp

Return to documentation for file (/tmp/ws/src/sick_scan_xd/include/sick_scan/tcp/SopasBase.hpp)

#include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
//
// SopasBase.h
//
//  Created on: 18.07.2011
//     Author: sick
//

#ifndef SOPASBASE_H
#define SOPASBASE_H

#include "sick_scan/tcp/BasicDatatypes.hpp"
// #include "sick_scan/tcp/datatypes/Scan.hpp"
#include "sick_scan/tcp/interfaces/tcp.hpp"

#include "colaa.hpp"
#include "colab.hpp"
#include <map>  // for std::map
#include "sick_scan/tcp/tools/Mutex.hpp"

namespace devices
{

class SopasEventMessage;
class SopasAnswer;

class SopasBase
{
public:
    static const std::string EVENTNAME_SUBSCRIBE_EVALCASES;
    static const std::string EVENTNAME_SUBSCRIBE_SCANS;
    static const std::string METHODNAME_LOGIN;
    static const std::string METHODNAME_LOGOUT;
    static const std::string METHODNAME_SET_SCANCONFIG;
    static const std::string METHODNAME_START_MEASURE;
    static const std::string METHODNAME_STOP_MEASURE;
    static const std::string VARIABLENAME_DEVICEIDENT;
    static const std::string VARIABLENAME_SCANCONFIG;
    static const std::string VARIABLENAME_DATAOUTPUTRANGE;
    static const std::string VARIABLENAME_SCANDATACONFIG;

    // sopas commands
    static const std::string COMMAND_Read_Variable_ByIndex;
    static const std::string COMMAND_Write_Variable_ByIndex;
    static const std::string COMMAND_Invoke_Method_ByIndex;
    static const std::string COMMAND_Method_Result_ByIndex;
    static const std::string COMMAND_Register_Event_ByIndex;
    static const std::string COMMAND_Send_Event_ByIndex; // receive data event

    static const std::string COMMAND_Read_Variable_Answer;
    static const std::string COMMAND_Write_Variable_Answer;
    static const std::string COMMAND_Invoke_Method_Answer;
    static const std::string COMMAND_Method_Result_Answer;
    static const std::string COMMAND_Register_Event_Answer;
    static const std::string COMMAND_Event_Acknowledge;

    static const std::string COMMAND_Read_Variable_ByName;
    static const std::string COMMAND_Write_Variable_ByName;
    static const std::string COMMAND_Invoke_Method_ByName;
    static const std::string COMMAND_Method_Result_ByName;
    static const std::string COMMAND_Register_Event_ByName;
    static const std::string COMMAND_Send_Event_ByName; // receive data event

    static const UINT16 INDEX_DEVICE_IDENT;

    enum SopasProtocol
    {
        CoLa_A,
        CoLa_B
    };

    enum SopasEncoding
    {
        ByName,
        ByIndex
    };

    enum SopasMessageType
    {
        MSG_UNKNOWN,
        //      MSG_READ_VARIABLE, ///< Read Variable
        //      MSG_WRITE_VARIABLE, ///< Write Variable
        //      MSG_INVOKE_METHOD, ///< Invoke Method
        //      MSG_METHOD_RESULT, ///< Method Result
        //      MSG_REGISTER_EVENT, ///< Register Event
        MSG_SEND_EVENT,
        MSG_READ_VARIABLE_ANSWER,
        MSG_WRITE_VARIABLE_ANSWER,
        MSG_INVOKE_METHOD_ANSWER,
        MSG_METHOD_RESULT_ANSWER,
        MSG_REGISTER_EVENT_ANSWER,
        MSG_EVENT_ACKNOWLEDGE,
        MSG_ERROR
    };

    typedef void (*DecoderFunction)(SopasEventMessage& frame);  //  Decoder for events

    SopasBase();

    virtual ~SopasBase();


    virtual bool init(SopasProtocol protocol,
                        std::string ipAddress,
                        UINT16 portNumber,
                        bool weWantScanData,
                        bool weWantFieldData,
                        bool readOnlyMode,
                        Tcp::DisconnectFunction disconnectFunction,
                        void* obj);

    bool connect();

    bool isConnected();

    bool disconnect();

    bool action_getScannerTypeAndVersion();


    void setReadOnlyMode(bool mode);

    bool isReadOnly();

    bool invokeMethod(const std::string& methodeName, BYTE* parameters, UINT16 parametersLength, SopasAnswer*& answer);

    bool invokeMethod(UINT16 index, BYTE* parameters, UINT16 parametersLength, SopasAnswer*& answer);

    bool readVariable(const std::string& variableName, SopasAnswer*& answer);

    bool readVariable(UINT16 index, SopasAnswer*& answer);

    bool writeVariable(const std::string& variableName, BYTE* parameters, UINT16 parametersLength);

    bool writeVariable(UINT16 index, BYTE* parameters, UINT16 parametersLength);

    bool registerEvent(const std::string& eventName);

    bool registerEvent(UINT16 index);

    bool unregisterEvent(const std::string& eventName);

    bool unregisterEvent(UINT16 index);

    void setEventCallbackFunction(DecoderFunction decoderFunction, const std::string& eventName)
    {
        m_decoderFunctionMapByName[eventName] = decoderFunction;
    }

    void setEventCallbackFunction(DecoderFunction decoderFunction, UINT16 eventIndex)
    {
        m_decoderFunctionMapByIndex[eventIndex] = decoderFunction;
    }


    double makeAngleValid(double angle);

    const std::string& getScannerName() const { return m_scannerName; }
    const std::string& getScannerVersion() const { return m_scannerVersion; }

    // Returns a timestamp in nanoseconds of the last received tcp message (or 0 if no message received)
    uint64_t getNanosecTimestampLastTcpMessageReceived(void);

    // Convert a SOPAS error code to readable text
    static std::string convertSopasErrorCodeToText(UINT16 errorCode);

protected:

    enum SopasCommand
    {
        CMD_UNKNOWN = 0,
        RI = 1,
        WI = 2,
        MI = 3,
        AI = 4,
        EI = 5,
        SI = 6,
        RA = 7,
        WA = 8,
        MA = 9,
        AA = 10,
        EA = 11,
        SA = 12,
        RN = 20,
        AN = 21,
        SN = 22,
        FA = 50
    };

    enum State
    {
        CONSTRUCTED
        ,
        CONNECTED
        //      , RUNNING
    };

    bool receiveAnswer(SopasCommand cmd, std::string name, UINT32 timeout, SopasAnswer*& answer);
    bool receiveAnswer_CoLa_A(SopasCommand cmd, std::string name, UINT32 timeout, SopasAnswer*& answer );
    bool receiveAnswer_CoLa_B(SopasCommand cmd, std::string name, UINT32 timeout, SopasAnswer*& answer );
    bool receiveAnswer(SopasCommand cmd, UINT16 index, UINT32 timeout, SopasAnswer*& answer );
    bool receiveAnswer_CoLa_A(SopasCommand cmd, UINT16 index, UINT32 timeout, SopasAnswer*& answer);
    bool receiveAnswer_CoLa_B(SopasCommand cmd, UINT16 index, UINT32 timeout, SopasAnswer*& answer);

    bool sendCommandBuffer(UINT8* buffer, UINT16 len);

    SopasCommand colaA_decodeCommand(std::string* rxData);

    SopasCommand stringToSopasCommand(const std::string& cmdString);
    std::string sopasCommandToString(SopasCommand cmd);

protected:
    // Decoder functions that need to be overwritten by derived classes
    virtual void evalCaseResultDecoder(SopasEventMessage& msg) = 0;
    virtual void scanDataDecoder(SopasEventMessage& msg) = 0;

    bool m_scanEventIsRegistered;
    bool m_fieldEventIsRegistered;
    bool m_weWantScanData;
    bool m_weWantFieldData;

    State m_state;
    std::string m_scannerName;
    std::string m_scannerVersion;

    bool m_beVerbose; //   true = Show extended status traces

    bool m_isLoggedIn;

private:
    // TCP
    bool openTcpConnection();
    void closeTcpConnection();

    static void readCallbackFunctionS(void* obj, UINT8* buffer, UINT32& numOfBytes);
    void readCallbackFunction(UINT8* buffer, UINT32& numOfBytes);

    SopasEventMessage findFrameInReceiveBuffer();

    void processFrame(SopasEventMessage& frame);
    void processFrame_CoLa_A(SopasEventMessage& frame);
    void processFrame_CoLa_B(SopasEventMessage& frame);
    void copyFrameToResposeBuffer(UINT32 frameLength);
    void removeFrameFromReceiveBuffer(UINT32 frameLength);

    // SOPAS / Cola
    SopasProtocol m_protocol;
    SopasEncoding m_encoding;
    void colaA_decodeScannerTypeAndVersion(std::string* rxData);
    void colaB_decodeScannerTypeAndVersion(UINT8* buffer, UINT16 pos);

private:
    typedef std::map<std::string, DecoderFunction> DecoderFunctionMapByName;
    typedef std::map<UINT16, DecoderFunction> DecoderFunctionMapByIndex;
    DecoderFunctionMapByName m_decoderFunctionMapByName;
    DecoderFunctionMapByIndex m_decoderFunctionMapByIndex;

//  DecoderFunction m_scanDecoderFunction;
//  DecoderFunction m_evalCaseDecoderFunction;

    typedef std::map<UINT16, std::string> IndexToNameMap;
    IndexToNameMap m_indexToNameMap;

    // Response buffer
    UINT32 m_numberOfBytesInResponseBuffer;
    UINT8 m_responseBuffer[1024];
    Mutex m_receiveDataMutex;

    // Receive buffer
    UINT32 m_numberOfBytesInReceiveBuffer;
    UINT8 m_receiveBuffer[25000];

    // TCP
    Tcp m_tcp;
    std::string m_ipAddress;
    UINT16 m_portNumber;

    bool m_readOnlyMode;
};


class SopasEventMessage
{
public:
    SopasEventMessage();

    ~SopasEventMessage() {}

    SopasEventMessage(BYTE* buffer, SopasBase::SopasProtocol protocol, UINT32 frameLength);

    SopasBase::SopasProtocol getProtocolType() const
    {
        return m_protocol;
    }

    SopasBase::SopasEncoding getEncodingType() const
    {
        return m_encoding;
    }

    SopasBase::SopasMessageType getMessageType() const
    {
        return m_messageType;
    }

    UINT32 size() const
    {
        return m_frameLength;
    }

    UINT32 getPayLoadLength() const;

    std::string getCommandString() const;

    BYTE* getPayLoad();

    INT32 getVariableIndex();

    std::string getVariableName();

    bool isValid() const { return (m_buffer != NULL); }

private:
    void detectEncoding();

    void detectMessageType();

private:
    BYTE* m_buffer;
    SopasBase::SopasProtocol m_protocol;
    UINT32 m_frameLength;
    SopasBase::SopasEncoding m_encoding;
    SopasBase::SopasMessageType m_messageType;
};

class SopasAnswer
{
public:
    SopasAnswer(const BYTE* answer, UINT32 answerLength);

    ~SopasAnswer();

    BYTE* getBuffer() { return m_answerBuffer; }

    UINT32 size() { return m_answerLength; }

    bool isValid() { return (m_answerBuffer != NULL); }

private:
    UINT32 m_answerLength;
    BYTE*  m_answerBuffer;
};

}   // namespace devices

#endif // SOPASBASE_H