Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #ifndef SWRI_CONSOLE_NODE_CLICK_HANDLER_H
00032 #define SWRI_CONSOLE_NODE_CLICK_HANDLER_H
00033
00034 #include <vector>
00035
00036 #include <boost/thread.hpp>
00037
00038 #include <QContextMenuEvent>
00039 #include <QObject>
00040 #include <QEvent>
00041 #include <QFuture>
00042 #include <QListView>
00043 #include <QMenu>
00044
00045 #include <ros/ros.h>
00046 #include <ros/service_client.h>
00047
00048 namespace swri_console
00049 {
00050 class NodeClickHandler : public QObject
00051 {
00052 Q_OBJECT
00053
00054 public Q_SLOTS:
00055 void logLevelClicked();
00056
00057 protected:
00058 bool eventFilter(QObject* obj, QEvent* event);
00059
00060 private:
00064 template <class T> void callServiceWorker(ros::ServiceClient& client, T* service, bool* success)
00065 {
00066 *success = client.call(*service);
00067 }
00068
00082 template <class T> bool callService(ros::ServiceClient& client, T& service, int timeout_secs = 5)
00083 {
00084 bool success = false;
00085 boost::thread svc_thread(&NodeClickHandler::callServiceWorker<T>, this, client, &service, &success);
00086
00087 if (svc_thread.try_join_for(boost::chrono::seconds(timeout_secs))) {
00088 return success;
00089 }
00090 svc_thread.interrupt();
00091 return false;
00092 }
00093
00094 bool showContextMenu(QListView* list, QContextMenuEvent* event);
00095 QMenu* createMenu(const QString& logger_name, const QString& current_level);
00096
00097 ros::NodeHandle nh_;
00098 std::string node_name_;
00099 std::vector<std::string> all_loggers_;
00100
00101 static const std::string ALL_LOGGERS;
00102 static const std::string GET_LOGGERS_SVC;
00103 static const std::string SET_LOGGER_LEVEL_SVC;
00104 };
00105 }
00106
00107 #endif //SWRI_CONSOLE_NODE_CLICK_HANDLER_H