Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
GUI_PTU::PTU_GUI Class Reference

#include <PTU_GUI.h>

Inheritance diagram for GUI_PTU::PTU_GUI:
Inheritance graph
[legend]

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
 
wxImagePanelleftPanel
 
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
 
wxImagePanelrightPanel
 
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
 

Detailed Description

Implementing GUIDialog

Definition at line 33 of file PTU_GUI.h.

Constructor & Destructor Documentation

GUI_PTU::PTU_GUI::PTU_GUI ( wxWindow *  parent)

Constructor

Definition at line 12 of file PTU_GUI.cpp.

Member Function Documentation

wxBitmap * GUI_PTU::PTU_GUI::createBitmap ( const sensor_msgs::Image::ConstPtr &  msg)
private

Definition at line 296 of file PTU_GUI.cpp.

sensor_msgs::JointState GUI_PTU::PTU_GUI::createJointCommand ( double  pan,
double  tilt,
double  panSpeed,
double  tiltSpeed 
)
private

Definition at line 326 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::initTopicList ( )
private

Definition at line 124 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnDialogClose ( wxCloseEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 162 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnImmChecked ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 211 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::onLeftImage ( const sensor_msgs::Image::ConstPtr &  msg)
private

Definition at line 316 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnLeftTopicChoice ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 168 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnListenChecked ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 215 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnPanScroll ( wxScrollEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 187 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnPanSpin ( wxSpinEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 191 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnPanSpinText ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 195 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnPTUChoice ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 180 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::onRightImage ( const sensor_msgs::Image::ConstPtr &  msg)
private

Definition at line 321 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnRightTopicChoice ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 174 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::onStateCommand ( const asr_flir_ptu_driver::State::ConstPtr &  msg)
private

Definition at line 270 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnTiltScroll ( wxScrollEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 199 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnTiltSpin ( wxSpinEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 203 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnTiltSpinText ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 207 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::onUpdate ( wxTimerEvent &  evt)
private

Definition at line 279 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::OnUpdateClicked ( wxCommandEvent &  event)
protectedvirtual

Reimplemented from GUI_PTU::GUIDialog.

Definition at line 222 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::updatePTUInfo ( )
private

Definition at line 65 of file PTU_GUI.cpp.

void GUI_PTU::PTU_GUI::updateSlidersFromParamServer ( )
private

Definition at line 78 of file PTU_GUI.cpp.

Member Data Documentation

bool GUI_PTU::PTU_GUI::immUpdate
private

Definition at line 56 of file PTU_GUI.h.

ros::Publisher GUI_PTU::PTU_GUI::jointStatePublisher
private

Definition at line 48 of file PTU_GUI.h.

ros::Subscriber GUI_PTU::PTU_GUI::jointStateSubscriber
private

Definition at line 49 of file PTU_GUI.h.

ros::Subscriber GUI_PTU::PTU_GUI::leftImageSubscriber
private

Definition at line 50 of file PTU_GUI.h.

bool GUI_PTU::PTU_GUI::listenForUpdates
private

Definition at line 57 of file PTU_GUI.h.

ros::NodeHandle GUI_PTU::PTU_GUI::nh
private

Definition at line 46 of file PTU_GUI.h.

ros::ServiceClient GUI_PTU::PTU_GUI::predict_client
private

Definition at line 53 of file PTU_GUI.h.

ros::NodeHandle GUI_PTU::PTU_GUI::ptu
private

Definition at line 47 of file PTU_GUI.h.

std::string GUI_PTU::PTU_GUI::ptu_name
private

Definition at line 55 of file PTU_GUI.h.

ros::Subscriber GUI_PTU::PTU_GUI::rightImageSubscriber
private

Definition at line 51 of file PTU_GUI.h.

int GUI_PTU::PTU_GUI::seq_num
private

Definition at line 58 of file PTU_GUI.h.

wxTimer* GUI_PTU::PTU_GUI::update_timer
private

Definition at line 54 of file PTU_GUI.h.

ros::ServiceClient GUI_PTU::PTU_GUI::updater
private

Definition at line 52 of file PTU_GUI.h.

bool GUI_PTU::PTU_GUI::use_path_prediction
private

Definition at line 59 of file PTU_GUI.h.


The documentation for this class was generated from the following files:


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