31 #ifndef SWRI_CONSOLE_NODE_CLICK_HANDLER_H 32 #define SWRI_CONSOLE_NODE_CLICK_HANDLER_H 36 #include <boost/thread.hpp> 38 #include <QContextMenuEvent> 66 *success = client.
call(*service);
85 boost::thread svc_thread(&NodeClickHandler::callServiceWorker<T>,
this, client, &service, &success);
87 if (svc_thread.try_join_for(boost::chrono::seconds(timeout_secs))) {
90 svc_thread.interrupt();
95 QMenu*
createMenu(
const QString& logger_name,
const QString& current_level);
107 #endif //SWRI_CONSOLE_NODE_CLICK_HANDLER_H
bool callService(ros::ServiceClient &client, T &service, int timeout_secs=5)
bool call(MReq &req, MRes &res)
bool showContextMenu(QListView *list, QContextMenuEvent *event)
void callServiceWorker(ros::ServiceClient &client, T *service, bool *success)
QMenu * createMenu(const QString &logger_name, const QString ¤t_level)
bool eventFilter(QObject *obj, QEvent *event)
static const std::string SET_LOGGER_LEVEL_SVC
static const std::string ALL_LOGGERS
std::vector< std::string > all_loggers_
static const std::string GET_LOGGERS_SVC