MKInterfaceConnection.hpp
Go to the documentation of this file.
00001 /*
00002  * MKInterfaceConnection.hpp
00003  *
00004  *  Created on: Nov 23, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef MKINTERFACECONNECTION_HPP_
00009 #define MKINTERFACECONNECTION_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <telekyb_serial/ThreadedSerialDevice.hpp>
00014 
00015 #include <telekyb_defines/MKDefines.hpp>
00016 #include <tk_mkinterface/MKData.hpp>
00017 #include <tk_mkinterface/MKValue.hpp>
00018 
00019 // Boost locking
00020 #include <boost/thread/mutex.hpp>
00021 
00022 // Options
00023 #include <tk_mkinterface/MKInterfaceConnectionOptions.hpp>
00024 
00025 
00026 // Queue
00027 #include <queue>
00028 
00029 // Visible Defines.  (for ROSINTERFACE)
00030 #define SET_QUEUE_SIZE 50
00031 #define UPDATE_QUEUE_SIZE 50
00032 #define ACTIVE_IDS_QUEUE_SIZE 10
00033 
00034 namespace TELEKYB_NAMESPACE
00035 {
00036 
00037 // TODO: This Element is not copyable. (Because it's a Listener!!!)
00038 
00039 class MKInterfaceConnection : public ThreadedSerialDevice, public SerialDeviceListener {
00040 protected:
00041         // The prefixpart of the message to UAV
00042         static const char setPrefix[];
00043         static const char updatePrefix[];
00044         static const char cmdOnlyPrefix[];
00045         static const char setActiveDataIDsPrefix[];
00046 
00047         //Options
00048         MKInterfaceConnectionOptions options;
00049 
00050         // The Data Structure for that connection
00051         MKData mkData;
00052         //MKInt activeDataIDs[ACTIVEDATA_SIZE];
00053         MKActiveIDs activeDataIDs;
00054 
00055         // Last Command 0 if not yet set. // This is important if other commands should send instantly
00056         boost::mutex lastCmdMutex;
00057         MKCommandsPacket lastCmd;
00058 
00059         // ActiveData IDs
00060         std::queue<MKActiveIDs> activeDataIDsQueue; // ASYNC
00061         MKActiveIDs* syncActiveDataIDsRequest; // SYNC -> != NULL for request
00062         boost::mutex syncActiveDataIDRequestMutex; // SYNC
00063 
00064         // Sync SET/UPDATE
00065         boost::mutex syncSetValueMutex; // SYNC
00066         boost::mutex syncUpdateValueMutex; //SYNC
00067 
00068         // these are != NULL if a sync Request is present
00069         MKInt* syncUpdateValue; // SYNC
00070         MKSingleValuePacket* syncSetValue; // SYNC
00071 
00072         // set and update Queues ASYNC
00073         std::queue<MKInt> updateQueue;
00074         std::queue<MKSingleValuePacket> setQueue;
00075 
00076         // Timer to determine package spacing.
00077         Timer asyncUpdateTimer;
00078         Timer asyncSetTimer;
00079         Timer asyncActiveIDsTimer;
00080 
00081         // specify the current sendQueue
00082         SendQueue currentSendQueue;
00083 
00084         // Queue Mutex <- so that we do not pop when calling front().
00085         boost::mutex queueMutex;
00086 
00087 
00088         // write // expects new Command! // stores lastCmd // checks queues // does not check Pointer
00089         void writeCommand(const MKCommandsPacket& command);
00090 
00091         // write Values & (old command). Does not check Queue / Checks pointers (Sync)
00092         void writeSetValue(); // SYNC
00093         void writeUpdateValue(); // SYNC
00094         void writeActiveDataIDsRequest(); // SYNC
00095 
00096         // setLastCommand <- Mutex protected!
00097         void setLastCmd(const MKCommandsPacket& command);
00098 
00099 
00100         // Handle Received Data
00101         void handleRecvSingleValuePacket(MKSingleValuePacket packet);
00102 
00103 
00104 
00105 public:
00106         // BEWARE. This throws SerialExceptions
00107         MKInterfaceConnection(const std::string& devicePath);
00108         virtual ~MKInterfaceConnection();
00109 
00110         // handle Data
00111         void handleReadSerialData(const std::vector<char>& data);
00112 
00113         // send command
00114         void sendCommand(const MKCommandsPacket& command);
00115 
00116         // set value <- reference to the acutal value! Setting stamp. so cannot be const!
00117         // Never use these for automatic progam logic!
00118         bool setValue(MKSingleValuePacket value);
00119 
00120         // update value <- get value write result in reference
00121         // Never use these for automatic program logic!
00122         bool updateValue(MKInt id);
00123 
00124         // sync Method to set active Data IDs;
00125         bool setActiveDataIDs(MKActiveIDs activeDataIDs_);
00126 
00127         // set value <- reference to the acutal value! // Store Value in List // Setting stamp. so cannot be const!
00128         void setValueAsync(MKSingleValuePacket value);
00129 
00130         // update value <- get value write result in reference
00131         void updateValueAsync(MKInt id); // Store Value in List
00132 
00133         // activeDataIDs can only be set async! // careful about the requirements!
00134         void setActiveDataIDsAsync(MKActiveIDs activeDataIDs_);
00135 
00136         // get the current MKActiveIDs
00137         MKActiveIDs getActiveDataIDs() const;
00138 
00139         // Data Accessors
00140         const MKData& getMKDataRef() const;
00141 
00142         // Listeners
00143         void registerMKDataListener(MKDataListener* listener);
00144         void unRegisterMKDataListener(MKDataListener* listener);
00145 
00146         // inputs
00147         static MKInterfaceConnection* findConnection(
00148                         const std::string& serialDeviceDirectory,
00149                         const std::string& serialDeviceNameRegEx,
00150                         std::vector<MKSingleValuePacket> conditions);
00151 
00152 };
00153 
00154 } // namespace
00155 
00156 #endif /* MKINTERFACECONNECTION_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


tk_mkinterface
Author(s): Martin Riedel
autogenerated on Wed Apr 24 2013 11:29:54