bb_estimation_controls.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * \file
00003  * \brief RVIZ plugin which provides simplified GUI based on Warehouse Viewer.
00004  *
00005  * $Id:$
00006  *
00007  * Copyright (C) Brno University of Technology
00008  *
00009  * This file is part of software developed by dcgm-robotics@FIT group.
00010  *
00011  * Author: Zdenek Materna (imaterna@fit.vutbr.cz)
00012  * Supervised by: Michal Spanel (spanel@fit.vutbr.cz)
00013  * Date: 5/4/2012
00014  * 
00015  * This file is free software: you can redistribute it and/or modify
00016  * it under the terms of the GNU Lesser General Public License as published by
00017  * the Free Software Foundation, either version 3 of the License, or
00018  * (at your option) any later version.
00019  * 
00020  * This file is distributed in the hope that it will be useful,
00021  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00022  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00023  * GNU Lesser General Public License for more details.
00024  * 
00025  * You should have received a copy of the GNU Lesser General Public License
00026  * along with this file.  If not, see <http://www.gnu.org/licenses/>.
00027  */
00028 
00029 #pragma once
00030 #ifndef BUT_BB_ESTIMATION_H
00031 #define BUT_BB_ESTIMATION_H
00032 
00033 #include <wx/wx.h>
00034 #include <wx/menu.h>
00035 #include <wx/panel.h>
00036 #include <wx/dialog.h>
00037 #include <wx/msgdlg.h>
00038 #include <wx/sizer.h>
00039 #include <wx/radiobox.h>
00040 #include <wx/checkbox.h>
00041 #include <ros/ros.h>
00042 #include <string.h>
00043 
00044 
00045 //#include <actionlib/client/simple_action_client.h>
00046 #include <actionlib/server/simple_action_server.h>
00047 #include <boost/thread.hpp>
00048 #include <boost/date_time/posix_time/posix_time.hpp>
00049 #include <map>
00050 #include <iostream>
00051 #include <sstream>
00052 
00053 #include "srs_assisted_arm_navigation/services_list.h"
00054 #include "srs_assisted_arm_navigation/topics_list.h"
00055 
00056 #include "srs_assisted_arm_navigation_msgs/ManualBBEstimationAction.h"
00057 
00058 
00059 #include <cv_bridge/cv_bridge.h>
00060 #include <opencv2/highgui/highgui.hpp>
00061 #include <opencv2/imgproc/imgproc.hpp>
00062 #include <opencv/cv.h>
00063 #include <image_transport/image_transport.h>
00064 
00065 
00066 namespace rviz
00067 {
00068     class WindowManagerInterface;
00069 }
00070 
00071 namespace srs_assisted_arm_navigation_ui {
00072 
00073 
00074 
00075 class CButBBEstimationControls : public wxPanel
00076 {
00077 public:
00079         CButBBEstimationControls(wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi );
00080     ~CButBBEstimationControls();
00081 
00082     void newData(int event, int x, int y);
00083 
00084 
00085 protected:
00086 
00087     //typedef actionlib::SimpleActionClient<ManualGraspingAction> grasping_action_client;
00088     typedef actionlib::SimpleActionServer<srs_assisted_arm_navigation_msgs::ManualBBEstimationAction> bb_est_action_server;
00089 
00091     rviz::WindowManagerInterface * m_wmi;
00092 
00093     ros::NodeHandle nh_;
00094 
00095     bb_est_action_server as_;
00096 
00097     image_transport::ImageTransport it_;
00098 
00099     //void ExecuteAction(const ManualBBEstimationGoalConstPtr &goal);
00100     void actionGoalCallback();
00101     void actionPreemptCallback();
00102 
00103     void OnOk(wxCommandEvent& event);
00104 
00105     void imageCallback(const sensor_msgs::ImageConstPtr& msg);
00106 
00107     wxButton * m_button_ok_;
00108 
00109     wxWindow *parent_;
00110 
00111 
00112     image_transport::Subscriber sub_image_;
00113 
00114     srs_assisted_arm_navigation_msgs::ManualBBEstimationGoalConstPtr goal_;
00115     srs_assisted_arm_navigation_msgs::ManualBBEstimationFeedback fb_;
00116 
00117     ros::Time max_time_;
00118 
00119     bool action_in_progress_;
00120 
00121     bool disable_video_;
00122 
00123 
00124     bool some_data_ready_;
00125     bool data_ready_;
00126 
00127     boost::mutex data_mutex_;
00128     int16_t p1_[2];
00129     int16_t p2_[2];
00130 
00131     bool is_video_flipped_;
00132 
00133     unsigned int image_width_;
00134     unsigned int image_height_;
00135 
00136 
00137     int butt_down_x_;
00138     int butt_down_y_;
00139 
00140     /*cv_bridge::CvImagePtr cv_ptr_; // original image
00141     cv_bridge::CvImagePtr cv_ptr_tmp_;*/
00142 
00143     boost::mutex image_mutex_;
00144     cv::Mat *image_;
00145     cv::Mat *image_tmp_;
00146 
00147     void timerCallback(const ros::TimerEvent& ev);
00148     ros::Timer timer_;
00149 
00150 private:
00151 
00152     DECLARE_EVENT_TABLE();
00153 
00154 
00155 };
00156 
00157 } // namespace
00158 
00159 #endif // BUT_GRASPING_H


srs_assisted_arm_navigation_ui
Author(s): Zdenek Materna
autogenerated on Sun Jan 5 2014 11:57:16