#include <PTU_GUI.h>
Public Member Functions | |
PTU_GUI (wxWindow *parent) | |
Public Member Functions inherited from GUI_PTU::GUIDialog | |
GUIDialog (wxWindow *parent, wxWindowID id=wxID_ANY, const wxString &title=wxT("PTU Visualisation"), const wxPoint &pos=wxDefaultPosition, const wxSize &size=wxSize(-1,-1), long style=wxDEFAULT_DIALOG_STYLE) | |
~GUIDialog () | |
Protected Member Functions | |
void | OnDialogClose (wxCloseEvent &event) |
void | OnImmChecked (wxCommandEvent &event) |
void | OnLeftTopicChoice (wxCommandEvent &event) |
void | OnListenChecked (wxCommandEvent &event) |
void | OnPanScroll (wxScrollEvent &event) |
void | OnPanSpin (wxSpinEvent &event) |
void | OnPanSpinText (wxCommandEvent &event) |
void | OnPTUChoice (wxCommandEvent &event) |
void | OnRightTopicChoice (wxCommandEvent &event) |
void | OnTiltScroll (wxScrollEvent &event) |
void | OnTiltSpin (wxSpinEvent &event) |
void | OnTiltSpinText (wxCommandEvent &event) |
void | OnUpdateClicked (wxCommandEvent &event) |
Private Member Functions | |
wxBitmap * | createBitmap (const sensor_msgs::Image::ConstPtr &msg) |
sensor_msgs::JointState | createJointCommand (double pan, double tilt, double panSpeed, double tiltSpeed) |
void | initTopicList () |
void | onLeftImage (const sensor_msgs::Image::ConstPtr &msg) |
void | onRightImage (const sensor_msgs::Image::ConstPtr &msg) |
void | onStateCommand (const asr_flir_ptu_driver::State::ConstPtr &msg) |
void | onUpdate (wxTimerEvent &evt) |
void | updatePTUInfo () |
void | updateSlidersFromParamServer () |
Private Attributes | |
bool | immUpdate |
ros::Publisher | jointStatePublisher |
ros::Subscriber | jointStateSubscriber |
ros::Subscriber | leftImageSubscriber |
bool | listenForUpdates |
ros::NodeHandle | nh |
ros::ServiceClient | predict_client |
ros::NodeHandle | ptu |
std::string | ptu_name |
ros::Subscriber | rightImageSubscriber |
int | seq_num |
wxTimer * | update_timer |
ros::ServiceClient | updater |
bool | use_path_prediction |
Additional Inherited Members | |
Protected Attributes inherited from GUI_PTU::GUIDialog | |
wxPanel * | cameraPanel |
wxCheckBox * | immCheck |
wxComboBox * | leftImageTopic |
wxImagePanel * | leftPanel |
wxCheckBox * | listenCheck |
wxStaticLine * | m_staticline2 |
wxStaticLine * | m_staticline3 |
wxStaticText * | m_staticText10 |
wxStaticText * | m_staticText11 |
wxStaticText * | m_staticText13 |
wxStaticText * | m_staticText14 |
wxStaticText * | m_staticText15 |
wxStaticText * | m_staticText16 |
wxStaticText * | m_staticText20 |
wxStaticText * | m_staticText21 |
wxStaticText * | m_staticText22 |
wxStaticText * | m_staticText23 |
wxStaticText * | m_staticText24 |
wxStaticText * | m_staticText25 |
wxStaticText * | m_staticText3 |
wxStaticText * | m_staticText4 |
wxStaticText * | m_staticText5 |
wxStaticText * | m_staticText6 |
wxSpinCtrl * | pan_accel |
wxSpinCtrl * | pan_base |
wxSpinCtrl * | pan_hold |
wxSpinCtrl * | pan_max |
wxSpinCtrl * | pan_min |
wxSpinCtrl * | pan_move |
wxSpinCtrl * | pan_target |
wxSpinCtrl * | pan_upper |
wxStaticText * | panAngleLabel |
wxSlider * | panSlider |
wxSpinCtrl * | panSpinner |
wxComboBox * | ptuChoice |
wxComboBox * | rightImageTopic |
wxImagePanel * | rightPanel |
wxStaticLine * | settingsDivider |
wxPanel * | settingsPanel |
wxSpinCtrl * | tilt_accel |
wxSpinCtrl * | tilt_base |
wxSpinCtrl * | tilt_hold |
wxSpinCtrl * | tilt_max |
wxSpinCtrl * | tilt_min |
wxSpinCtrl * | tilt_move |
wxSpinCtrl * | tilt_target |
wxSpinCtrl * | tilt_upper |
wxStaticText * | tiltAngleLabel |
wxSlider * | tiltSlider |
wxSpinCtrl * | tiltSpinner |
wxButton * | updateButton |
GUI_PTU::PTU_GUI::PTU_GUI | ( | wxWindow * | parent | ) |
Constructor
Definition at line 12 of file PTU_GUI.cpp.
|
private |
Definition at line 296 of file PTU_GUI.cpp.
|
private |
Definition at line 326 of file PTU_GUI.cpp.
|
private |
Definition at line 124 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 162 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 211 of file PTU_GUI.cpp.
|
private |
Definition at line 316 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 168 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 215 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 187 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 191 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 195 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 180 of file PTU_GUI.cpp.
|
private |
Definition at line 321 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 174 of file PTU_GUI.cpp.
|
private |
Definition at line 270 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 199 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 203 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 207 of file PTU_GUI.cpp.
|
private |
Definition at line 279 of file PTU_GUI.cpp.
|
protectedvirtual |
Reimplemented from GUI_PTU::GUIDialog.
Definition at line 222 of file PTU_GUI.cpp.
|
private |
Definition at line 65 of file PTU_GUI.cpp.
|
private |
Definition at line 78 of file PTU_GUI.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |