31 #ifndef MAPVIZ_SELECT_SERVICE_DIALOG_H 32 #define MAPVIZ_SELECT_SERVICE_DIALOG_H 37 #include <boost/shared_ptr.hpp> 100 static std::string selectService(
const std::string& datatype, QWidget* parent=0);
118 void setDatatypeFilter(
const std::string& datatype);
125 std::string selectedService()
const;
132 void fetchServices();
137 void updateDisplayedServices();
146 void displayUpdateError(
const QString);
149 std::vector<std::string> filterServices();
150 void timerEvent(QTimerEvent *);
151 void closeEvent(QCloseEvent *);
170 #endif //MAPVIZ_SELECT_SERVICE_DIALOG_H std::vector< std::string > known_services_
void servicesFetched(ServiceStringVector services)
std::string allowed_datatype_
QPushButton * cancel_button_
const std::string & allowed_datatype_
std::vector< std::string > displayed_services_
boost::shared_ptr< ServiceUpdaterThread > worker_thread_
int fetch_services_timer_id_
QT_END_NAMESPACE typedef std::vector< std::string > ServiceStringVector
Q_DECLARE_METATYPE(ServiceStringVector)
ServiceUpdaterThread(ros::NodeHandle &nh, const std::string &allowed_datatype, QObject *parent)
void fetchingFailed(const QString error_msg)
QListWidget * list_widget_