awesome_camera_display.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 PR2_INTERACTIVE_MANIPULATION_CAMERA_DISPLAY_H
00031 #define PR2_INTERACTIVE_MANIPULATION_CAMERA_DISPLAY_H
00032 
00033 #include <QObject>
00034 
00035 #include <OGRE/OgreMaterial.h>
00036 #include <OGRE/OgreRenderTargetListener.h>
00037 
00038 #include <sensor_msgs/CameraInfo.h>
00039 
00040 #include <message_filters/subscriber.h>
00041 #include <tf/message_filter.h>
00042 
00043 #include "rviz/image/image_display_base.h"
00044 #include "rviz/image/ros_image_texture.h"
00045 #include "rviz/render_panel.h"
00046 
00047 namespace Ogre
00048 {
00049 class SceneNode;
00050 class ManualObject;
00051 class Rectangle2D;
00052 class Camera;
00053 }
00054 
00055 namespace rviz
00056 {
00057 class EnumProperty;
00058 class FloatProperty;
00059 class IntProperty;
00060 class RenderPanel;
00061 class RosTopicProperty;
00062 class DisplayGroupVisibilityProperty;
00063 
00072 class AwesomeCameraDisplay: public rviz::ImageDisplayBase, public Ogre::RenderTargetListener
00073 {
00074 Q_OBJECT
00075 public:
00076   AwesomeCameraDisplay();
00077   virtual ~AwesomeCameraDisplay();
00078 
00079   // Overrides from Display
00080   virtual void onInitialize();
00081   virtual void fixedFrameChanged();
00082   virtual void update( float wall_dt, float ros_dt );
00083   virtual void reset();
00084 
00085   // Overrides from Ogre::RenderTargetListener
00086   virtual void preRenderTargetUpdate( const Ogre::RenderTargetEvent& evt );
00087   virtual void postRenderTargetUpdate( const Ogre::RenderTargetEvent& evt );
00088 
00089   static const QString BACKGROUND;
00090   static const QString OVERLAY;
00091   static const QString BOTH;
00092 
00093 protected:
00094   // overrides from Display
00095   virtual void onEnable();
00096   virtual void onDisable();
00097 
00098   ROSImageTexture texture_;
00099   RenderPanel* render_panel_;
00100   PanelDockWidget* render_panel_dock_widget_;
00101 
00102 private Q_SLOTS:
00103   void forceRender();
00104   void updateAlpha();
00105 
00106   virtual void updateQueueSize();
00107 
00108   void panelVisibilityChanged( bool );
00109   void showPanelPropertyChanged( );
00110 
00111 private:
00112   void subscribe();
00113   void unsubscribe();
00114 
00115   virtual void processMessage(const sensor_msgs::Image::ConstPtr& msg);
00116   void caminfoCallback( const sensor_msgs::CameraInfo::ConstPtr& msg );
00117 
00118   void updateCamera();
00119 
00120   void clear();
00121   void updateStatus();
00122 
00123   Ogre::SceneNode* bg_scene_node_;
00124   Ogre::SceneNode* fg_scene_node_;
00125 
00126   Ogre::ManualObject* bg_screen_rect_;
00127   Ogre::MaterialPtr bg_material_;
00128 
00129   Ogre::ManualObject* fg_screen_rect_;
00130   Ogre::MaterialPtr fg_material_;
00131 
00132   message_filters::Subscriber<sensor_msgs::CameraInfo> caminfo_sub_;
00133   tf::MessageFilter<sensor_msgs::CameraInfo>* caminfo_tf_filter_;
00134 
00135   FloatProperty* alpha_property_;
00136   EnumProperty* image_position_property_;
00137   FloatProperty* zoom_property_;
00138   FloatProperty* near_clip_property_;
00139   DisplayGroupVisibilityProperty* visibility_property_;
00140   BoolProperty* show_panel_property_;
00141 
00142   sensor_msgs::CameraInfo::ConstPtr current_caminfo_;
00143   boost::mutex caminfo_mutex_;
00144 
00145   bool new_caminfo_;
00146 
00147   bool force_render_;
00148 
00149   uint32_t vis_bit_;
00150 };
00151 
00152 } // namespace rviz
00153 
00154  #endif


pr2_interactive_manipulation_frontend
Author(s): Jonathan Binney
autogenerated on Mon Oct 6 2014 12:06:28