00001 /* 00002 * MKROSInterface.hpp 00003 * 00004 * Created on: Nov 29, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef MKROSINTERFACE_HPP_ 00009 #define MKROSINTERFACE_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 00013 #include <tk_mkinterface/MKROSInterfaceOptions.hpp> 00014 #include <tk_mkinterface/MKData.hpp> 00015 00016 #include <ros/ros.h> 00017 00018 #include <telekyb_srvs/StringOutput.h> 00019 #include <telekyb_srvs/IntArrayInput.h> 00020 #include <telekyb_srvs/MKValueInputOutput.h> 00021 #include <std_srvs/Empty.h> 00022 00023 #include <telekyb_msgs/TKCommands.h> 00024 #include <telekyb_msgs/MKValue.h> 00025 #include <telekyb_msgs/MKValues.h> 00026 00027 namespace TELEKYB_NAMESPACE { 00028 00029 // Forward Definition 00030 class MKInterface; 00031 00032 00033 class MKROSInterface : public MKDataListener { 00034 protected: 00035 MKROSInterfaceOptions options; 00036 00037 MKInterface& mkInterface; // Object that we interface to ROS 00038 00039 int robotID; 00040 00044 ros::NodeHandle mainNodeHandle; // Programs main Nodehandle 00045 ros::NodeHandle robotIDNodeHandle; 00046 00047 // BatteryTimer 00048 ros::Timer batteryTimer; 00049 void batteryTimerCB(const ros::TimerEvent& event); 00050 00054 void setupServices(); 00055 00056 ros::ServiceServer getMainMKNodeHandle; 00057 00058 // Sync 00059 ros::ServiceServer setActiveDataIDs; 00060 ros::ServiceServer setMKValue; 00061 ros::ServiceServer updateMKValue; 00062 ros::ServiceServer doDriftEstim; 00063 ros::ServiceServer setEmergency; 00064 00065 // Async with Messages? 00066 bool getMainMKNodeHandleCB( 00067 telekyb_srvs::StringOutput::Request& request, 00068 telekyb_srvs::StringOutput::Response& response); 00069 00070 bool setActiveDataIDsCB( 00071 telekyb_srvs::IntArrayInput::Request& request, 00072 telekyb_srvs::IntArrayInput::Response& response); 00073 00074 bool setMKValueCB( 00075 telekyb_srvs::MKValueInputOutput::Request& request, 00076 telekyb_srvs::MKValueInputOutput::Response& response); 00077 00078 bool updateMKValueCB( 00079 telekyb_srvs::MKValueInputOutput::Request& request, 00080 telekyb_srvs::MKValueInputOutput::Response& response); 00081 00082 bool doDriftEstimCB( 00083 std_srvs::Empty::Request& request, 00084 std_srvs::Empty::Response& response); 00085 00086 bool setEmergencyCB( 00087 std_srvs::Empty::Request& request, 00088 std_srvs::Empty::Response& response); 00089 00090 00095 ros::Subscriber commandsSub; 00096 void commandsCB(const telekyb_msgs::TKCommands::ConstPtr& msg); 00097 00098 // Async Values 00099 ros::Subscriber setMKValueAsyncSub; 00100 ros::Subscriber updateMKValueAsyncSub; 00101 void setMKValueAsyncCB(const telekyb_msgs::MKValue::ConstPtr& msg); 00102 void updateMKValueAsyncCB(const telekyb_msgs::MKValue::ConstPtr& msg); 00103 00104 00105 // MKValue Publisher 00106 telekyb_msgs::MKValues mkDataMirror; 00107 void setupMKDataMirror(); 00108 00109 ros::Publisher mkValuePublisher; 00110 ros::Publisher mkValueArrayPublisher; 00111 00112 00113 public: 00114 MKROSInterface(MKInterface& mkInterface_, int robotID_); 00115 virtual ~MKROSInterface(); 00116 00117 void dataValueUpdated(MKValue* value); 00118 00119 void activateCommandsCB(); 00120 void deActiavteCommandsCB(); 00121 00122 }; 00123 00124 } /* namespace telekyb */ 00125 #endif /* MKROSINTERFACE_HPP_ */