PTU_GUI.h
Go to the documentation of this file.
1 
8 #ifndef __PTU_GUI__
9 #define __PTU_GUI__
10 
16 #include "GUI.h"
17 #include "ros/ros.h"
18 #include "sensor_msgs/JointState.h"
19 #include "sensor_msgs/Image.h"
20 #include "std_srvs/Empty.h"
21 #include <wx/wx.h>
22 #include "asr_flir_ptu_driver/State.h"
23 #include "asr_flir_ptu_driver/Predict.h"
24 
25 #define DEFAULT_PREFFEREDLEFT "/left/image_color"
26 #define DEFAULT_PREFFEREDRIGHT "/right/image_color"
27 
29 
30 namespace GUI_PTU {
31 
33 class PTU_GUI : public GUIDialog
34 {
35  private:
36  void updatePTUInfo();
37  void initTopicList();
38  void onUpdate(wxTimerEvent& evt);
39  wxBitmap* createBitmap(const sensor_msgs::Image::ConstPtr& msg);
40  void onLeftImage(const sensor_msgs::Image::ConstPtr& msg);
41  void onRightImage(const sensor_msgs::Image::ConstPtr& msg);
42  void onStateCommand(const asr_flir_ptu_driver::State::ConstPtr& msg);
43  sensor_msgs::JointState createJointCommand(double pan, double tilt, double panSpeed, double tiltSpeed);
45 
54  wxTimer* update_timer;
55  std::string ptu_name;
56  bool immUpdate;
58  int seq_num;
60 
61 // const static wxString DEFAULT_PREFFEREDLEFT = wxString::FromUTF8("/left/image_color");
62 // const static wxString DEFAULT_PREFFEREDRIGHT = wxString::FromUTF8("/right/image_color");
63  protected:
64  // Handlers for GUIDialog events.
65  void OnDialogClose( wxCloseEvent& event );
66  void OnLeftTopicChoice( wxCommandEvent& event );
67  void OnRightTopicChoice( wxCommandEvent& event );
68  void OnPTUChoice( wxCommandEvent& event );
69  void OnPanScroll( wxScrollEvent& event );
70  void OnPanSpin( wxSpinEvent& event );
71  void OnPanSpinText( wxCommandEvent& event );
72  void OnTiltScroll( wxScrollEvent& event );
73  void OnTiltSpin( wxSpinEvent& event );
74  void OnTiltSpinText( wxCommandEvent& event );
75  void OnImmChecked( wxCommandEvent& event );
76  void OnListenChecked( wxCommandEvent& event );
77  void OnUpdateClicked( wxCommandEvent& event );
78  public:
80  PTU_GUI( wxWindow* parent );
82 
83 };
84 
85 }
86 
87 #endif // __PTU_GUI__
ros::NodeHandle nh
Definition: PTU_GUI.h:46
wxTimer * update_timer
Definition: PTU_GUI.h:54
void OnTiltSpinText(wxCommandEvent &event)
Definition: PTU_GUI.cpp:207
std::string ptu_name
Definition: PTU_GUI.h:55
bool use_path_prediction
Definition: PTU_GUI.h:59
ros::ServiceClient predict_client
Definition: PTU_GUI.h:53
ros::ServiceClient updater
Definition: PTU_GUI.h:52
void OnPanScroll(wxScrollEvent &event)
Definition: PTU_GUI.cpp:187
void onLeftImage(const sensor_msgs::Image::ConstPtr &msg)
Definition: PTU_GUI.cpp:316
PTU_GUI(wxWindow *parent)
Definition: PTU_GUI.cpp:12
void OnPanSpinText(wxCommandEvent &event)
Definition: PTU_GUI.cpp:195
void OnTiltScroll(wxScrollEvent &event)
Definition: PTU_GUI.cpp:199
void OnListenChecked(wxCommandEvent &event)
Definition: PTU_GUI.cpp:215
void OnLeftTopicChoice(wxCommandEvent &event)
Definition: PTU_GUI.cpp:168
bool immUpdate
Definition: PTU_GUI.h:56
ros::Subscriber jointStateSubscriber
Definition: PTU_GUI.h:49
void onRightImage(const sensor_msgs::Image::ConstPtr &msg)
Definition: PTU_GUI.cpp:321
bool listenForUpdates
Definition: PTU_GUI.h:57
void OnPanSpin(wxSpinEvent &event)
Definition: PTU_GUI.cpp:191
ros::Subscriber rightImageSubscriber
Definition: PTU_GUI.h:51
ros::Subscriber leftImageSubscriber
Definition: PTU_GUI.h:50
void onStateCommand(const asr_flir_ptu_driver::State::ConstPtr &msg)
Definition: PTU_GUI.cpp:270
wxBitmap * createBitmap(const sensor_msgs::Image::ConstPtr &msg)
Definition: PTU_GUI.cpp:296
void OnTiltSpin(wxSpinEvent &event)
Definition: PTU_GUI.cpp:203
sensor_msgs::JointState createJointCommand(double pan, double tilt, double panSpeed, double tiltSpeed)
Definition: PTU_GUI.cpp:326
void OnImmChecked(wxCommandEvent &event)
Definition: PTU_GUI.cpp:211
Definition: GUI.h:41
ros::Publisher jointStatePublisher
Definition: PTU_GUI.h:48
ros::NodeHandle ptu
Definition: PTU_GUI.h:47
void OnRightTopicChoice(wxCommandEvent &event)
Definition: PTU_GUI.cpp:174
void updatePTUInfo()
Definition: PTU_GUI.cpp:65
void OnPTUChoice(wxCommandEvent &event)
Definition: PTU_GUI.cpp:180
void OnDialogClose(wxCloseEvent &event)
Definition: PTU_GUI.cpp:162
void OnUpdateClicked(wxCommandEvent &event)
Definition: PTU_GUI.cpp:222
void onUpdate(wxTimerEvent &evt)
Definition: PTU_GUI.cpp:279
void updateSlidersFromParamServer()
Definition: PTU_GUI.cpp:78
Class GUIDialog.
Definition: GUI.h:46
void initTopicList()
Definition: PTU_GUI.cpp:124


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Mon Dec 2 2019 03:15:17