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, public Ogre::RenderTargetListener
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 
00093   void setQueueSize( int size );
00094   int getQueueSize();
00095 
00096   // Overrides from Display
00097   virtual void fixedFrameChanged();
00098   virtual void createProperties();
00099   virtual void update(float wall_dt, float ros_dt);
00100   virtual void reset();
00101 
00102   // Overrides from Ogre::RenderTargetListener
00103   virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt);
00104   virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt);
00105 
00106 protected Q_SLOTS:
00108   void setWrapperEnabled( bool enabled );
00109 
00110 protected:
00111 
00112   // overrides from Display
00113   virtual void onEnable();
00114   virtual void onDisable();
00115 
00116   void subscribe();
00117   void unsubscribe();
00118 
00119   void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
00120 
00121   void updateCamera();
00122 
00123   void clear();
00124   void updateStatus();
00125 
00126   void onTransportEnumOptions(V_string& choices);
00127   void onImagePositionEnumOptions(V_string& choices);
00128 
00129   Ogre::SceneNode* bg_scene_node_;
00130   Ogre::SceneNode* fg_scene_node_;
00131 
00132   Ogre::Rectangle2D* bg_screen_rect_;
00133   Ogre::MaterialPtr bg_material_;
00134 
00135   Ogre::Rectangle2D* fg_screen_rect_;
00136   Ogre::MaterialPtr fg_material_;
00137 
00138   float alpha_;
00139   float zoom_;
00140   std::string topic_;
00141   std::string transport_;
00142   std::string image_position_;
00143 
00144   message_filters::Subscriber<sensor_msgs::CameraInfo> caminfo_sub_;
00145   tf::MessageFilter<sensor_msgs::CameraInfo>* caminfo_tf_filter_;
00146 
00147   FloatPropertyWPtr alpha_property_;
00148   ROSTopicStringPropertyWPtr topic_property_;
00149   EditEnumPropertyWPtr transport_property_;
00150   EditEnumPropertyWPtr image_position_property_;
00151   FloatPropertyWPtr zoom_property_;
00152   IntPropertyWPtr queue_size_property_;
00153 
00154   sensor_msgs::CameraInfo::ConstPtr current_caminfo_;
00155   boost::mutex caminfo_mutex_;
00156 
00157   bool new_caminfo_;
00158 
00159   ROSImageTexture texture_;
00160 
00161   RenderPanel* render_panel_;
00162 
00163   bool force_render_;
00164 
00165   PanelDockWidget* panel_container_;
00166 };
00167 
00168 } // namespace rviz
00169 
00170  #endif


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32