23 #ifndef __PLUGINS_ROS_WEBVIEW_THREAD_H_ 24 #define __PLUGINS_ROS_WEBVIEW_THREAD_H_ 26 #include <core/threading/thread.h> 27 #include <core/utils/lockptr.h> 28 #include <aspect/logging.h> 29 #include <aspect/configurable.h> 30 #include <aspect/clock.h> 31 #include <aspect/webview.h> 32 #include <plugins/ros/aspect/ros.h> 34 #include <ros/service_server.h> 35 #include <fawkes_msgs/WebviewUrlRegistration.h> 36 #include <fawkes_msgs/WebviewNavRegistration.h> 60 bool srv_register_cb(fawkes_msgs::WebviewUrlRegistration::Request &req,
61 fawkes_msgs::WebviewUrlRegistration::Response &resp);
63 bool srv_unregister_cb(fawkes_msgs::WebviewUrlRegistration::Request &req,
64 fawkes_msgs::WebviewUrlRegistration::Response &resp);
66 bool srv_add_nav_cb(fawkes_msgs::WebviewNavRegistration::Request &req,
67 fawkes_msgs::WebviewNavRegistration::Response &resp);
69 bool srv_remove_nav_cb(fawkes_msgs::WebviewNavRegistration::Request &req,
70 fawkes_msgs::WebviewNavRegistration::Response &resp);
73 protected:
virtual void run() { Thread::run(); }
76 ros::ServiceServer __srv_register;
77 ros::ServiceServer __srv_unregister;
78 ros::ServiceServer __srv_add_nav;
79 ros::ServiceServer __srv_remove_nav;
81 std::map<std::string, ROSWebviewRequestProcessor *> __procs;
82 std::map<std::string, std::string> __nav_entries;
Thread aspect that allows to obtain the current time from the clock.
Thread aspect to get access to a ROS node handle.
ROSWebviewThread()
Constructor.
virtual void finalize()
Finalize the thread.
Thread class encapsulation of pthreads.
virtual void init()
Initialize the thread.
virtual ~ROSWebviewThread()
Destructor.
virtual void run()
Stub to see name in backtrace for easier debugging.
Thread aspect to log output.
Thread aspect to access configuration data.
Convert webview requests to ROS service calls.
Thread aspect to provide web pages via Webview.
virtual void loop()
Code to execute in the thread.