object_control_pane.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * \file
00003  *
00004  * $Id$
00005  *
00006  * Copyright (C) Brno University of Technology
00007  *
00008  * This file is part of software developed by dcgm-robotics@FIT group.
00009  *
00010  * Author: Tomas Lokaj
00011  * Supervised by: Michal Spanel (spanel@fit.vutbr.cz)
00012  * Date: 09/08/2012
00013  *
00014  * This file is free software: you can redistribute it and/or modify
00015  * it under the terms of the GNU Lesser General Public License as published by
00016  * the Free Software Foundation, either version 3 of the License, or
00017  * (at your option) any later version.
00018  *
00019  * This file is distributed in the hope that it will be useful,
00020  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00021  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00022  * GNU Lesser General Public License for more details.
00023  *
00024  * You should have received a copy of the GNU Lesser General Public License
00025  * along with this file.  If not, see <http://www.gnu.org/licenses/>.
00026  */
00027 #pragma once
00028 #ifndef OBJECT_CONTROL_PANE_H
00029 #define OBJECT_CONTROL_PANE_H
00030 
00031 #include <ros/ros.h>
00032 #include <ros/service.h>
00033 
00034 #include <rviz/window_manager_interface.h>
00035 #include <rviz/visualization_manager.h>
00036 
00037 #include <srs_object_database_msgs/GetObjectId.h>
00038 #include <srs_object_database_msgs/GetMesh.h>
00039 #include <srs_interaction_primitives/PositionClicked.h>
00040 #include <srs_interaction_primitives/services_list.h>
00041 #include <srs_interaction_primitives/topics_list.h>
00042 
00043 #include <tf/tf.h>
00044 #include <tf/transform_listener.h>
00045 
00046 #include <wx/wx.h>
00047 #include <wx/menu.h>
00048 #include <wx/panel.h>
00049 #include <wx/dialog.h>
00050 #include <wx/choice.h>
00051 #include <wx/textctrl.h>
00052 #include <wx/stattext.h>
00053 #include <wx/colordlg.h>
00054 #include <wx/clrpicker.h>
00055 
00056 #include <boost/shared_ptr.hpp>
00057 
00058 #include <string>
00059 #include <vector>
00060 
00061 #define DefaultFrame_PARAM "/srs_ui_but/default_frame"
00062 #define CLICKABLE_POSITIONS_TOPIC "obj_manager_positions"
00063 
00064 const int ID_ADD_OBJECT_BUTTON(101);
00065 const int ID_OBJECTS_CHOICE(102);
00066 const int ID_STATUS_LABEL(103);
00067 const int ID_DESCRIPTION_LABEL(104);
00068 const int ID_DESCRIPTION_TEXT(105);
00069 const int ID_COLOR_LABEL(106);
00070 const int ID_FRAME_LABEL(107);
00071 const int ID_FRAME_TEXT(108);
00072 const int ID_POS_LABEL(109);
00073 const int ID_POSX_TEXT(110);
00074 const int ID_POSY_TEXT(111);
00075 const int ID_POSZ_TEXT(112);
00076 const int ID_ADDED_OBJECTS_CHOICE(113);
00077 const int ID_REMOVE_OBJECT_BUTTON(114);
00078 const int ID_COLOR_CLRPICKER(115);
00079 const int ID_CLICKABLEPOS_BUTTON(116);
00080 
00081 namespace rviz
00082 {
00083 class WindowManagerInterface;
00084 }
00085 
00086 namespace srs_ui_but
00087 {
00088 
00089 class CObjectControlPane : public wxPanel
00090 {
00091 public:
00095   CObjectControlPane(wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi);
00096 
00097   /*
00098    * @brief Enables or disables
00099    */
00100   void setEnabled(bool enabled)
00101   {
00102     enabled_ = enabled;
00103     if (enabled)
00104       setStatus("Enabled");
00105     else
00106       setStatus("Disabled");
00107   }
00108 
00109   std::vector<std::string> getObjectIds();
00110 
00111 protected:
00115   void OnAddObject(wxCommandEvent& event);
00116 
00120   void OnRemoveObject(wxCommandEvent& event);
00121 
00125   void OnClickablePositions(wxCommandEvent& event);
00126 
00130   void setStatus(std::string text)
00131   {
00132     m_statusLabel->SetLabel(wxString::FromUTF8((const char*)text.c_str()));
00133   }
00134 
00135   void poseClickedCallback(const srs_interaction_primitives::PositionClickedConstPtr &msg);
00136 
00137   bool enabled_;
00138 
00139   rviz::WindowManagerInterface * m_wmi;
00140 
00141   int object_count_;
00142   std::string default_frame_;
00143 
00144   wxButton *m_addObjectButton, *m_removeObjectButton, *m_clickablePositions;
00145   wxChoice *m_objectsChoice, *m_addedObjectsChoice;
00146   wxTextCtrl *m_descriptionText, *m_frameText, *m_posxText, *m_posyText, *m_poszText;
00147   wxStaticText *m_descriptionLabel, *m_statusLabel, *m_frameLabel, *m_posLabel, *m_colorLabel;
00148   //wxColourDialog *m_colorDialog;
00149   wxColourPickerCtrl *m_colorClrpicker;
00150 
00151   // Service clients
00152   ros::ServiceClient get_models_client_, get_model_mesh_client_, add_object_client_, remove_primitive_client_,
00153                      clickable_positions_client_;
00154 
00155   // Get node handle
00156   ros::NodeHandle nh_;
00157 
00158   // Containers
00159   std::map<int, const char*> database_objects_;
00160   std::vector<int> database_ids_;
00161   std::vector<std::string> database_descs_;
00162   std::vector<geometry_msgs::Vector3> database_sizes_;
00163 
00164   // // Topic soubscribers
00165   ros::Subscriber pose_clicked_subscriber_;
00166 
00167   // Transform listener
00168   tf::TransformListener *tfListener_;
00169 
00170   // Transformer
00171   tf::Transformer transformer_;
00172 
00173   // Transformations
00174   tf::StampedTransform robotToFfTf_;
00175 
00176 private:
00177 DECLARE_EVENT_TABLE()
00178 
00179 };
00180 
00181 } // namespace srs_ui_but
00182 
00183 // OBJECT_CONTROL_PANE_H
00184 #endif
00185 


srs_ui_but
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz), Tomas Lokaj
autogenerated on Mon Oct 6 2014 08:49:30