camera_display.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 RVIZ_CAMERA_DISPLAY_H
00031 #define RVIZ_CAMERA_DISPLAY_H
00032 
00033 #include <QObject>
00034 
00035 #include "rviz/display.h"
00036 #include "rviz/render_panel.h"
00037 #include "rviz/properties/forwards.h"
00038 #include "rviz/image/ros_image_texture.h"
00039 
00040 #include <sensor_msgs/CameraInfo.h>
00041 
00042 #include <OGRE/OgreMaterial.h>
00043 #include <OGRE/OgreRenderTargetListener.h>
00044 
00045 #include <message_filters/subscriber.h>
00046 #include <tf/message_filter.h>
00047 
00048 namespace Ogre
00049 {
00050 class SceneNode;
00051 class ManualObject;
00052 class Rectangle2D;
00053 class Camera;
00054 }
00055 
00056 class QWidget;
00057 
00058 namespace rviz
00059 {
00060 
00061 class RenderPanel;
00062 class PanelDockWidget;
00063 
00068 class CameraDisplay: public Display
00069 {
00070 Q_OBJECT
00071 public:
00072   CameraDisplay();
00073   virtual ~CameraDisplay();
00074 
00075   virtual void onInitialize();
00076 
00077   float getAlpha() { return alpha_; }
00078   void setAlpha( float alpha );
00079 
00080   const std::string& getTopic() { return topic_; }
00081   void setTopic(const std::string& topic);
00082 
00083   const std::string& getTransport() { return transport_; }
00084   void setTransport(const std::string& transport);
00085 
00086   const std::string& getImagePosition() { return image_position_; }
00087   void setImagePosition(const std::string& image_position);
00088 
00089   float getZoom() { return zoom_; }
00090   void setZoom( float zoom );
00091 
00092   // Overrides from Display
00093   virtual void targetFrameChanged();
00094   virtual void fixedFrameChanged();
00095   virtual void createProperties();
00096   virtual void update(float wall_dt, float ros_dt);
00097   virtual void reset();
00098 
00099 protected Q_SLOTS:
00101   void setWrapperEnabled( bool enabled );
00102 
00103 protected:
00104 
00105   // overrides from Display
00106   virtual void onEnable();
00107   virtual void onDisable();
00108 
00109   void subscribe();
00110   void unsubscribe();
00111 
00112   void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
00113 
00114   void updateCamera();
00115 
00116   void clear();
00117   void updateStatus();
00118 
00119   void onTransportEnumOptions(V_string& choices);
00120   void onImagePositionEnumOptions(V_string& choices);
00121 
00122   Ogre::SceneNode* bg_scene_node_;
00123   Ogre::SceneNode* fg_scene_node_;
00124 
00125   Ogre::Rectangle2D* bg_screen_rect_;
00126   Ogre::MaterialPtr bg_material_;
00127 
00128   Ogre::Rectangle2D* fg_screen_rect_;
00129   Ogre::MaterialPtr fg_material_;
00130 
00131   float alpha_;
00132   float zoom_;
00133   std::string topic_;
00134   std::string transport_;
00135   std::string image_position_;
00136 
00137   message_filters::Subscriber<sensor_msgs::CameraInfo> caminfo_sub_;
00138   tf::MessageFilter<sensor_msgs::CameraInfo>* caminfo_tf_filter_;
00139 
00140   FloatPropertyWPtr alpha_property_;
00141   ROSTopicStringPropertyWPtr topic_property_;
00142   EditEnumPropertyWPtr transport_property_;
00143   EditEnumPropertyWPtr image_position_property_;
00144   FloatPropertyWPtr zoom_property_;
00145 
00146   sensor_msgs::CameraInfo::ConstPtr current_caminfo_;
00147   boost::mutex caminfo_mutex_;
00148 
00149   bool new_caminfo_;
00150 
00151   ROSImageTexture texture_;
00152 
00153   class Panel;
00154 
00155   Panel* render_panel_;
00156 
00157   bool force_render_;
00158 
00159   PanelDockWidget* panel_container_;
00160 
00161   class RenderListener : public Ogre::RenderTargetListener
00162   {
00163   public:
00164     RenderListener(CameraDisplay* display);
00165     virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt);
00166     virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt);
00167 
00168   private:
00169     CameraDisplay* display_;
00170   };
00171 
00172   class Panel: public RenderPanel
00173   {
00174   public:
00175     Panel( CameraDisplay* display, QWidget* parent = 0 );
00176     void setActive( bool active );
00177     void updateRenderWindow();
00178   protected:
00179     virtual void showEvent( QShowEvent *event );
00180     CameraDisplay* display_;
00181     bool active_;
00182   private:
00183     RenderListener render_listener_;
00184   };
00185 };
00186 
00187 } // namespace rviz
00188 
00189  #endif


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52