00001 00008 #ifndef __PTU_GUI__ 00009 #define __PTU_GUI__ 00010 00016 #include "GUI.h" 00017 #include "ros/ros.h" 00018 #include "sensor_msgs/JointState.h" 00019 #include "sensor_msgs/Image.h" 00020 #include "std_srvs/Empty.h" 00021 #include <wx/wx.h> 00022 #include "asr_flir_ptu_driver/State.h" 00023 #include "asr_flir_ptu_driver/Predict.h" 00024 00025 #define DEFAULT_PREFFEREDLEFT "/left/image_color" 00026 #define DEFAULT_PREFFEREDRIGHT "/right/image_color" 00027 00029 00030 namespace GUI_PTU { 00031 00033 class PTU_GUI : public GUIDialog 00034 { 00035 private: 00036 void updatePTUInfo(); 00037 void initTopicList(); 00038 void onUpdate(wxTimerEvent& evt); 00039 wxBitmap* createBitmap(const sensor_msgs::Image::ConstPtr& msg); 00040 void onLeftImage(const sensor_msgs::Image::ConstPtr& msg); 00041 void onRightImage(const sensor_msgs::Image::ConstPtr& msg); 00042 void onStateCommand(const asr_flir_ptu_driver::State::ConstPtr& msg); 00043 sensor_msgs::JointState createJointCommand(double pan, double tilt, double panSpeed, double tiltSpeed); 00044 void updateSlidersFromParamServer(); 00045 00046 ros::NodeHandle nh; 00047 ros::NodeHandle ptu; 00048 ros::Publisher jointStatePublisher; 00049 ros::Subscriber jointStateSubscriber; 00050 ros::Subscriber leftImageSubscriber; 00051 ros::Subscriber rightImageSubscriber; 00052 ros::ServiceClient updater; 00053 ros::ServiceClient predict_client; 00054 wxTimer* update_timer; 00055 std::string ptu_name; 00056 bool immUpdate; 00057 bool listenForUpdates; 00058 int seq_num; 00059 bool use_path_prediction; 00060 00061 // const static wxString DEFAULT_PREFFEREDLEFT = wxString::FromUTF8("/left/image_color"); 00062 // const static wxString DEFAULT_PREFFEREDRIGHT = wxString::FromUTF8("/right/image_color"); 00063 protected: 00064 // Handlers for GUIDialog events. 00065 void OnDialogClose( wxCloseEvent& event ); 00066 void OnLeftTopicChoice( wxCommandEvent& event ); 00067 void OnRightTopicChoice( wxCommandEvent& event ); 00068 void OnPTUChoice( wxCommandEvent& event ); 00069 void OnPanScroll( wxScrollEvent& event ); 00070 void OnPanSpin( wxSpinEvent& event ); 00071 void OnPanSpinText( wxCommandEvent& event ); 00072 void OnTiltScroll( wxScrollEvent& event ); 00073 void OnTiltSpin( wxSpinEvent& event ); 00074 void OnTiltSpinText( wxCommandEvent& event ); 00075 void OnImmChecked( wxCommandEvent& event ); 00076 void OnListenChecked( wxCommandEvent& event ); 00077 void OnUpdateClicked( wxCommandEvent& event ); 00078 public: 00080 PTU_GUI( wxWindow* parent ); 00082 00083 }; 00084 00085 } 00086 00087 #endif // __PTU_GUI__