gripper_click_rviz_ui.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef GRIPPER_CLICK_RVIZ_UI
00031 #define GRIPPER_CLICK_RVIZ_UI
00032 
00033 #include <string>
00034 
00035 #include <sensor_msgs/Image.h>
00036 #include <sensor_msgs/CameraInfo.h>
00037 #include <stereo_msgs/DisparityImage.h>
00038 
00039 #include <OGRE/OgreSceneNode.h>
00040 #include <OGRE/OgreSceneManager.h>
00041 
00042 #include <wx/event.h>
00043 
00044 #include <rviz/visualization_manager.h>
00045 #include "rviz_interaction_tools/gripper.h"
00046 #include "rviz_interaction_tools/disparity_renderer.h"
00047 #include <rviz/status_level.h>
00048 
00049 #include "pr2_gripper_click/gripper_click_plugin.h"
00050 
00051 #include "gripper_click_ui.h"
00052 
00053 #ifdef DEBUG_DISPLAY
00054 #include "rviz_interaction_tools/line.h"
00055 #endif
00056 
00057 namespace rviz_interaction_tools {
00058 class ImageOverlay;
00059 }
00060 
00061 namespace rviz {
00062 class WindowManagerInterface;
00063 class RenderPanel;
00064 class VisualizationManager;
00065 }
00066 
00067 namespace Ogre {
00068 class Light;
00069 }
00070 
00071 namespace pr2_gripper_click {
00072 
00073 // Displays the camera + disparity images in a window
00074 // allows to switch between 'plugins' that provide their own mouse interaction
00075 // and visual elements for the 3D display
00076 template<class ActionClass>
00077 class GripperClickRvizUI : public GripperClickFrameBase {
00078 
00079 public:
00080 
00081   typedef typename ActionClass::_action_result_type::_result_type ResultType;
00082   typedef typename ActionClass::_action_goal_type::_goal_type GoalType;
00083 
00084   enum ActionState{ IDLE, ACCEPTED, CANCELED };
00085 
00086   GripperClickRvizUI(rviz::VisualizationManager *visualization_manager);
00087 
00088   virtual ~GripperClickRvizUI();
00089 
00090   // @return state of the user interaction (@see ActionState)
00091   ActionState getState(){return action_state_;}
00092 
00093   // update frame buffer
00094   virtual void update(float wall_dt, float ros_dt);
00095 
00096   // add a new plugin to the list. Will take ownership.
00097   void addPlugin( GripperClickPlugin<ActionClass>* plugin );
00098 
00099   // Pass a new goal to all plugins
00100   bool setGoal( const typename GoalType::ConstPtr &goal );
00101 
00102   // transfer control & show selected plugin
00103   void setActivePlugin( unsigned index );
00104 
00105   // @brief get result for ActionClass
00106   // @return false if there is no valid result for the current plugin
00107   bool getResult( ResultType &result );
00108 
00109   // show / hide the window
00110   void show();
00111   void hide();
00112 
00113   // status text, describes if there is some error (e.g. a tf error)
00114   std::string getStatusText() const { return status_text_; }
00115   rviz::status_levels::StatusLevel getStatusLevel() const { return status_level_; }
00116 
00117   // set a new image / depth combination to be displayed
00118   void setImage( const sensor_msgs::Image &image,
00119       const stereo_msgs::DisparityImage &disparity_image,
00120       const sensor_msgs::CameraInfo &camera_info );
00121 
00122 protected:
00123 
00124   // try to retrieve tf transform, set error status otherwise
00125   bool getTransform( std::string frame, Ogre::Vector3 &position, Ogre::Quaternion &orientation );
00126 
00127   // change text displaed at bottom of window
00128   void setBottomLabelText( const std::string &text );
00129 
00130   // change rviz status level & text
00131   void setStatus(rviz::status_levels::StatusLevel level, const std::string& text);
00132 
00133   // handle mouse movements, clicks etc.
00134   virtual void onRenderWindowMouseEvents( wxMouseEvent& event );
00135 
00136   // listeners for buttons
00137   virtual void acceptButtonClicked( wxCommandEvent& );
00138   virtual void cancelButtonClicked( wxCommandEvent& );
00139 
00140   //called when the user selects a different plugin
00141   virtual void onPluginChoice( wxCommandEvent& event );
00142 
00143   ActionState action_state_;
00144 
00145   rviz::RenderPanel* render_panel_;
00146 
00147   Ogre::SceneManager* scene_manager_;
00148   Ogre::SceneNode* camera_node_;
00149 
00150   rviz_interaction_tools::DisparityRenderer *disparity_renderer_;
00151 
00152   rviz_interaction_tools::Gripper* gripper_;
00153 
00154   rviz_interaction_tools::Gripper* main_win_gripper_;
00155   Ogre::SceneNode* main_win_camera_node_;
00156   rviz_interaction_tools::DisparityRenderer *main_win_disparity_renderer_;
00157 
00158   rviz::VisualizationManager *vis_manager_;
00159 
00160   std::string camera_frame_;
00161 
00162   Ogre::Light* gripper_light_;
00163 
00164   rviz_interaction_tools::ImageOverlay *image_overlay_;
00165 
00166   std::vector< GripperClickPlugin<ActionClass>* > plugins_;
00167   unsigned active_plugin_;
00168 
00169   rviz::status_levels::StatusLevel status_level_;
00170   std::string status_text_;
00171 
00172 #ifdef DEBUG_DISPLAY
00173   rviz_interaction_tools::Line *line_;
00174 #endif
00175 
00176 };
00177 
00178 
00179 
00180 }
00181 
00182 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


pr2_gripper_click
Author(s): Matei Ciocarlie
autogenerated on Tue Oct 30 2012 07:55:20