#include <PTU_GUI.h>
|  | 
|  | PTU_GUI (wxWindow *parent) | 
|  | 
|  | 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 () | 
|  | 
Implementing GUIDialog 
Definition at line 33 of file PTU_GUI.h.
◆ PTU_GUI()
      
        
          | GUI_PTU::PTU_GUI::PTU_GUI | ( | wxWindow * | parent | ) |  | 
      
 
 
◆ createBitmap()
  
  | 
        
          | wxBitmap * GUI_PTU::PTU_GUI::createBitmap | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  |  | private | 
 
 
◆ createJointCommand()
  
  | 
        
          | sensor_msgs::JointState GUI_PTU::PTU_GUI::createJointCommand | ( | double | pan, |  
          |  |  | double | tilt, |  
          |  |  | double | panSpeed, |  
          |  |  | double | tiltSpeed |  
          |  | ) |  |  |  | private | 
 
 
◆ initTopicList()
  
  | 
        
          | void GUI_PTU::PTU_GUI::initTopicList | ( |  | ) |  |  | private | 
 
 
◆ OnDialogClose()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnDialogClose | ( | wxCloseEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnImmChecked()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnImmChecked | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ onLeftImage()
  
  | 
        
          | void GUI_PTU::PTU_GUI::onLeftImage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  |  | private | 
 
 
◆ OnLeftTopicChoice()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnLeftTopicChoice | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnListenChecked()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnListenChecked | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnPanScroll()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnPanScroll | ( | wxScrollEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnPanSpin()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnPanSpin | ( | wxSpinEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnPanSpinText()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnPanSpinText | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnPTUChoice()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnPTUChoice | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ onRightImage()
  
  | 
        
          | void GUI_PTU::PTU_GUI::onRightImage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  |  | private | 
 
 
◆ OnRightTopicChoice()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnRightTopicChoice | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ onStateCommand()
  
  | 
        
          | void GUI_PTU::PTU_GUI::onStateCommand | ( | const asr_flir_ptu_driver::State::ConstPtr & | msg | ) |  |  | private | 
 
 
◆ OnTiltScroll()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnTiltScroll | ( | wxScrollEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnTiltSpin()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnTiltSpin | ( | wxSpinEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ OnTiltSpinText()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnTiltSpinText | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ onUpdate()
  
  | 
        
          | void GUI_PTU::PTU_GUI::onUpdate | ( | wxTimerEvent & | evt | ) |  |  | private | 
 
 
◆ OnUpdateClicked()
  
  | 
        
          | void GUI_PTU::PTU_GUI::OnUpdateClicked | ( | wxCommandEvent & | event | ) |  |  | protectedvirtual | 
 
 
◆ updatePTUInfo()
  
  | 
        
          | void GUI_PTU::PTU_GUI::updatePTUInfo | ( |  | ) |  |  | private | 
 
 
◆ updateSlidersFromParamServer()
  
  | 
        
          | void GUI_PTU::PTU_GUI::updateSlidersFromParamServer | ( |  | ) |  |  | private | 
 
 
◆ immUpdate
  
  | 
        
          | bool GUI_PTU::PTU_GUI::immUpdate |  | private | 
 
 
◆ jointStatePublisher
◆ jointStateSubscriber
◆ leftImageSubscriber
◆ listenForUpdates
  
  | 
        
          | bool GUI_PTU::PTU_GUI::listenForUpdates |  | private | 
 
 
◆ nh
◆ predict_client
◆ ptu
◆ ptu_name
  
  | 
        
          | std::string GUI_PTU::PTU_GUI::ptu_name |  | private | 
 
 
◆ rightImageSubscriber
◆ seq_num
  
  | 
        
          | int GUI_PTU::PTU_GUI::seq_num |  | private | 
 
 
◆ update_timer
  
  | 
        
          | wxTimer* GUI_PTU::PTU_GUI::update_timer |  | private | 
 
 
◆ updater
◆ use_path_prediction
  
  | 
        
          | bool GUI_PTU::PTU_GUI::use_path_prediction |  | private | 
 
 
The documentation for this class was generated from the following files: