Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <boost/bind.hpp>
00031
00032 #include <OGRE/OgreManualObject.h>
00033 #include <OGRE/OgreMaterialManager.h>
00034 #include <OGRE/OgreRectangle2D.h>
00035 #include <OGRE/OgreRenderSystem.h>
00036 #include <OGRE/OgreRenderWindow.h>
00037 #include <OGRE/OgreRoot.h>
00038 #include <OGRE/OgreSceneManager.h>
00039 #include <OGRE/OgreSceneNode.h>
00040 #include <OGRE/OgreTextureManager.h>
00041 #include <OGRE/OgreViewport.h>
00042
00043 #include <tf/transform_listener.h>
00044
00045 #include "rviz/display_context.h"
00046 #include "rviz/frame_manager.h"
00047 #include "rviz/render_panel.h"
00048 #include "rviz/validate_floats.h"
00049
00050 #include <sensor_msgs/image_encodings.h>
00051
00052 #include "image_display.h"
00053
00054 namespace rviz
00055 {
00056
00057 ImageDisplay::ImageDisplay()
00058 : ImageDisplayBase()
00059 , texture_()
00060 {
00061 normalize_property_ = new BoolProperty( "Normalize Range", true,
00062 "If set to true, will try to estimate the range of possible values from the received images.",
00063 this, SLOT( updateNormalizeOptions() ));
00064
00065 min_property_ = new FloatProperty( "Min Value", 0.0, "Value which will be displayed as black.", this, SLOT( updateNormalizeOptions() ));
00066
00067 max_property_ = new FloatProperty( "Max Value", 1.0, "Value which will be displayed as white.", this, SLOT( updateNormalizeOptions() ));
00068
00069 median_buffer_size_property_ = new IntProperty( "Median window", 5, "Window size for median filter used for computin min/max.",
00070 this, SLOT( updateNormalizeOptions() ) );
00071
00072 got_float_image_ = false;
00073 }
00074
00075 void ImageDisplay::onInitialize()
00076 {
00077 {
00078 static uint32_t count = 0;
00079 std::stringstream ss;
00080 ss << "ImageDisplay" << count++;
00081 img_scene_manager_ = Ogre::Root::getSingleton().createSceneManager(Ogre::ST_GENERIC, ss.str());
00082 }
00083
00084 img_scene_node_ = img_scene_manager_->getRootSceneNode()->createChildSceneNode();
00085
00086 {
00087 static int count = 0;
00088 std::stringstream ss;
00089 ss << "ImageDisplayObject" << count++;
00090
00091 screen_rect_ = new Ogre::Rectangle2D(true);
00092 screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00093 screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00094
00095 ss << "Material";
00096 material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00097 material_->setSceneBlending( Ogre::SBT_REPLACE );
00098 material_->setDepthWriteEnabled(false);
00099 material_->setReceiveShadows(false);
00100 material_->setDepthCheckEnabled(false);
00101
00102 material_->getTechnique(0)->setLightingEnabled(false);
00103 Ogre::TextureUnitState* tu = material_->getTechnique(0)->getPass(0)->createTextureUnitState();
00104 tu->setTextureName(texture_.getTexture()->getName());
00105 tu->setTextureFiltering( Ogre::TFO_NONE );
00106
00107 material_->setCullingMode(Ogre::CULL_NONE);
00108 Ogre::AxisAlignedBox aabInf;
00109 aabInf.setInfinite();
00110 screen_rect_->setBoundingBox(aabInf);
00111 screen_rect_->setMaterial(material_->getName());
00112 img_scene_node_->attachObject(screen_rect_);
00113 }
00114
00115 render_panel_ = new RenderPanel();
00116 render_panel_->getRenderWindow()->setAutoUpdated(false);
00117 render_panel_->getRenderWindow()->setActive( false );
00118
00119 render_panel_->resize( 640, 480 );
00120 render_panel_->initialize(img_scene_manager_, context_);
00121
00122 setAssociatedWidget( render_panel_ );
00123
00124 render_panel_->setAutoRender(false);
00125 render_panel_->setOverlaysEnabled(false);
00126 render_panel_->getCamera()->setNearClipDistance( 0.01f );
00127
00128 updateNormalizeOptions();
00129 }
00130
00131 ImageDisplay::~ImageDisplay()
00132 {
00133 ImageDisplayBase::unsubscribe();
00134 delete render_panel_;
00135 delete screen_rect_;
00136 img_scene_node_->getParentSceneNode()->removeAndDestroyChild( img_scene_node_->getName() );
00137 }
00138
00139 void ImageDisplay::onEnable()
00140 {
00141 ImageDisplayBase::subscribe();
00142 render_panel_->getRenderWindow()->setActive(true);
00143 }
00144
00145 void ImageDisplay::onDisable()
00146 {
00147 render_panel_->getRenderWindow()->setActive(false);
00148 ImageDisplayBase::unsubscribe();
00149 clear();
00150 }
00151
00152 void ImageDisplay::updateNormalizeOptions()
00153 {
00154 if (got_float_image_)
00155 {
00156 bool normalize = normalize_property_->getBool();
00157
00158 normalize_property_->setHidden(false);
00159 min_property_->setHidden(normalize);
00160 max_property_->setHidden(normalize);
00161 median_buffer_size_property_->setHidden(!normalize);
00162
00163 texture_.setNormalizeFloatImage( normalize, min_property_->getFloat(), max_property_->getFloat());
00164 texture_.setMedianFrames( median_buffer_size_property_->getInt() );
00165 }
00166 else
00167 {
00168 normalize_property_->setHidden(true);
00169 min_property_->setHidden(true);
00170 max_property_->setHidden(true);
00171 median_buffer_size_property_->setHidden(true);
00172 }
00173 }
00174
00175 void ImageDisplay::clear()
00176 {
00177 texture_.clear();
00178
00179 if( render_panel_->getCamera() )
00180 {
00181 render_panel_->getCamera()->setPosition(Ogre::Vector3(999999, 999999, 999999));
00182 }
00183 }
00184
00185 void ImageDisplay::update( float wall_dt, float ros_dt )
00186 {
00187 try
00188 {
00189 texture_.update();
00190
00191
00192 float win_width = render_panel_->width();
00193 float win_height = render_panel_->height();
00194
00195 float img_width = texture_.getWidth();
00196 float img_height = texture_.getHeight();
00197
00198 if ( img_width != 0 && img_height != 0 && win_width !=0 && win_height != 0 )
00199 {
00200 float img_aspect = img_width / img_height;
00201 float win_aspect = win_width / win_height;
00202
00203 if ( img_aspect > win_aspect )
00204 {
00205 screen_rect_->setCorners(-1.0f, 1.0f * win_aspect/img_aspect, 1.0f, -1.0f * win_aspect/img_aspect, false);
00206 }
00207 else
00208 {
00209 screen_rect_->setCorners(-1.0f * img_aspect/win_aspect, 1.0f, 1.0f * img_aspect/win_aspect, -1.0f, false);
00210 }
00211 }
00212
00213 render_panel_->getRenderWindow()->update();
00214 }
00215 catch( UnsupportedImageEncoding& e )
00216 {
00217 setStatus(StatusProperty::Error, "Image", e.what());
00218 }
00219 }
00220
00221 void ImageDisplay::reset()
00222 {
00223 ImageDisplayBase::reset();
00224 clear();
00225 }
00226
00227
00228 void ImageDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
00229 {
00230 bool got_float_image = msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1 ||
00231 msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1 ||
00232 msg->encoding == sensor_msgs::image_encodings::TYPE_16SC1 ||
00233 msg->encoding == sensor_msgs::image_encodings::MONO16;
00234
00235 if ( got_float_image != got_float_image_ )
00236 {
00237 got_float_image_ = got_float_image;
00238 updateNormalizeOptions();
00239 }
00240 texture_.addMessage(msg);
00241 }
00242
00243 }
00244
00245 #include <pluginlib/class_list_macros.h>
00246 PLUGINLIB_EXPORT_CLASS( rviz::ImageDisplay, rviz::Display )