18 #include "sensor_msgs/JointState.h" 19 #include "sensor_msgs/Image.h" 20 #include "std_srvs/Empty.h" 22 #include "asr_flir_ptu_driver/State.h" 23 #include "asr_flir_ptu_driver/Predict.h" 25 #define DEFAULT_PREFFEREDLEFT "/left/image_color" 26 #define DEFAULT_PREFFEREDRIGHT "/right/image_color" 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);
void OnTiltSpinText(wxCommandEvent &event)
ros::ServiceClient predict_client
ros::ServiceClient updater
void OnPanScroll(wxScrollEvent &event)
void onLeftImage(const sensor_msgs::Image::ConstPtr &msg)
PTU_GUI(wxWindow *parent)
void OnPanSpinText(wxCommandEvent &event)
void OnTiltScroll(wxScrollEvent &event)
void OnListenChecked(wxCommandEvent &event)
void OnLeftTopicChoice(wxCommandEvent &event)
ros::Subscriber jointStateSubscriber
void onRightImage(const sensor_msgs::Image::ConstPtr &msg)
void OnPanSpin(wxSpinEvent &event)
ros::Subscriber rightImageSubscriber
ros::Subscriber leftImageSubscriber
void onStateCommand(const asr_flir_ptu_driver::State::ConstPtr &msg)
wxBitmap * createBitmap(const sensor_msgs::Image::ConstPtr &msg)
void OnTiltSpin(wxSpinEvent &event)
sensor_msgs::JointState createJointCommand(double pan, double tilt, double panSpeed, double tiltSpeed)
void OnImmChecked(wxCommandEvent &event)
ros::Publisher jointStatePublisher
void OnRightTopicChoice(wxCommandEvent &event)
void OnPTUChoice(wxCommandEvent &event)
void OnDialogClose(wxCloseEvent &event)
void OnUpdateClicked(wxCommandEvent &event)
void onUpdate(wxTimerEvent &evt)
void updateSlidersFromParamServer()