#include <node_click_handler.h>
Definition at line 50 of file node_click_handler.h.
◆ callService()
template<class T >
bool swri_console::NodeClickHandler::callService |
( |
ros::ServiceClient & |
client, |
|
|
T & |
service, |
|
|
int |
timeout_secs = 5 |
|
) |
| |
|
inlineprivate |
Attempts to call a ROS service. Will time out and return false if the service call does not return within a specified time.
This is so ugly, but some sort of hack like this is necessary for keeping the UI responsive; ROS service clients do not have any built-in timeout mechanism, so we have to wrap our own around the service call. If we don't, a call to a hanged node could spin forever.
- Template Parameters
-
- Parameters
-
client | An initialized ros::ServiceClient |
service | An instance of the ROS service |
timeout_secs | The number of seconds to wait before timing out |
- Returns
- true if the service call completed successfully, otherwise false
Definition at line 82 of file node_click_handler.h.
◆ callServiceWorker()
template<class T >
void swri_console::NodeClickHandler::callServiceWorker |
( |
ros::ServiceClient & |
client, |
|
|
T * |
service, |
|
|
bool * |
success |
|
) |
| |
|
inlineprivate |
◆ createMenu()
QMenu * swri_console::NodeClickHandler::createMenu |
( |
const QString & |
logger_name, |
|
|
const QString & |
current_level |
|
) |
| |
|
private |
◆ eventFilter()
bool swri_console::NodeClickHandler::eventFilter |
( |
QObject * |
obj, |
|
|
QEvent * |
event |
|
) |
| |
|
protected |
◆ logLevelClicked
void swri_console::NodeClickHandler::logLevelClicked |
( |
| ) |
|
|
slot |
◆ showContextMenu()
bool swri_console::NodeClickHandler::showContextMenu |
( |
QListView * |
list, |
|
|
QContextMenuEvent * |
event |
|
) |
| |
|
private |
Normally this call should return very quickly, but we don't want the GUI to hang if the roscore is stuck, so add a timeout. The value is pretty arbitrary, but we also want to give enough time for this to still respond over a slow network link, so it shouldn't be too small.
Definition at line 69 of file node_click_handler.cpp.
◆ ALL_LOGGERS
const std::string swri_console::NodeClickHandler::ALL_LOGGERS = "All Loggers" |
|
staticprivate |
◆ all_loggers_
std::vector<std::string> swri_console::NodeClickHandler::all_loggers_ |
|
private |
◆ GET_LOGGERS_SVC
const std::string swri_console::NodeClickHandler::GET_LOGGERS_SVC = "/get_loggers" |
|
staticprivate |
◆ nh_
◆ node_name_
std::string swri_console::NodeClickHandler::node_name_ |
|
private |
◆ SET_LOGGER_LEVEL_SVC
const std::string swri_console::NodeClickHandler::SET_LOGGER_LEVEL_SVC = "/set_logger_level" |
|
staticprivate |
The documentation for this class was generated from the following files: