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