00001 /* 00002 * MKInterface.hpp 00003 * 00004 * Created on: Dec 8, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef MKINTERFACE_HPP_ 00009 #define MKINTERFACE_HPP_ 00010 00011 //TODO: Create BaseClass for MKINTERFACE AND TELEKYBSYSTEM. 00012 00013 #include <telekyb_defines/telekyb_defines.hpp> 00014 00015 #include <telekyb_defines/MKDefines.hpp> 00016 00017 #include <telekyb_interface/OptionController.hpp> 00018 00019 #include <ros/ros.h> 00020 00021 #include <telekyb_msgs/MKValue.h> 00022 00023 #include <boost/thread/mutex.hpp> 00024 00025 namespace TELEKYB_INTERFACE_NAMESPACE { 00026 00027 struct MKCompleteSingeValue { 00028 int id; 00029 int value; 00030 std::string name; 00031 ros::Time stamp; 00032 00033 MKCompleteSingeValue() { 00034 id = -1; 00035 } 00036 }; 00037 00038 00039 class MKInterface { 00040 private: 00041 MKInterface(int robotID_, const std::string& mainHandleNamespace); 00042 00043 protected: 00044 int robotID; 00045 ros::NodeHandle mainNodeHandle; 00046 00047 OptionController* optionController; 00048 void createOptionController(); 00049 // System check. 00050 bool isOk() const; 00051 00055 ros::Publisher setMKValueAsyncPub; 00056 ros::Publisher updateMKValueAsyncPub; 00057 00058 // Updates mkValues automatically. 00059 ros::Subscriber mkValueSub; 00060 00061 MKCompleteSingeValue valueArray[MKDataDefines::MKDATAIDS_NUM]; 00062 boost::mutex valueArrayMutex; 00063 00064 public: 00065 virtual ~MKInterface(); 00066 00067 static MKInterface* getMKInterface(int robotID_, double blockTimeOut_ = 2.0); 00068 00069 OptionController* getOptionController() const; 00070 00071 // Mapped Functions 00072 bool doDriftEstim(); 00073 bool setActiveDataIDs(MKActiveIDs activeIDs); 00074 bool setMKValue(MKSingleValuePacket value); 00075 bool updateMKValue(MKSingleValuePacket& value); // updates Value 00076 00077 bool setEmergency(); 00078 00079 void setMKValueAsync(MKSingleValuePacket value); 00080 void updateMKValueAsync(MKInt id); 00081 00082 void recvMKValue(const telekyb_msgs::MKValue::ConstPtr& msg); 00083 00084 MKCompleteSingeValue getMKCompleteSingeValue(int id) const; 00085 00086 bool updateAllMKValues(); 00087 void updateAllMKValuesAsync(); 00088 00089 }; 00090 00091 } /* namespace telekyb_interface */ 00092 #endif /* MKINTERFACE_HPP_ */