backdrop_display.cpp
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 #include <sstream>
00031 
00032 #include <OGRE/OgreSceneNode.h>
00033 #include <OGRE/OgreSceneManager.h>
00034 #include <OGRE/OgreMaterialManager.h>
00035 #include <OGRE/OgreManualObject.h>
00036 
00037 #include <tf/transform_listener.h>
00038 
00039 #include <rviz/visualization_manager.h>
00040 #include <rviz/properties/property.h> 
00041 //#include <rviz/properties/property_manager.h> Note: Removed in Hydro
00042 #include <rviz/frame_manager.h>
00043 
00044 #include <rviz/image/ros_image_texture.h>
00045 #include "backdrop_display.h"
00046 
00047 namespace rviz_backdrop
00048 {
00049 
00050 
00051 
00052 // Hydro re-write, see groovy-devel for how code was before.
00053 // scale 0.01, scene node NULL, teture update(nh)
00054 // Removed initializations.
00055 BackdropDisplay::BackdropDisplay()
00056   : Display()
00057   , scale_( 0.01 )
00058 {
00059   // ---------- Empty Intentionally ---------- //
00060 }
00061 
00062 
00063 // After the parent rviz::Display::initialize() does its own setup, it
00064 // calls the subclass's onInitialize() function.  This is where we
00065 // instantiate all the workings of the class.
00066 void BackdropDisplay::onInitialize()
00067 {
00068   // Make an Ogre::SceneNode to contain all our visuals.
00069   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00070   
00071   // Create a unique name for the material.
00072   static int count = 0;
00073   std::stringstream ss;
00074   ss << "BackdropDisplay" << count++ << "Material";
00075 
00076   // Create the material and connect it to the texture_.
00077   image_material_ =
00078     Ogre::MaterialManager::getSingleton().create( ss.str(),
00079                                                   Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00080   image_material_->getTechnique( 0 )->setLightingEnabled( false );
00081   Ogre::TextureUnitState* tu = image_material_->getTechnique( 0 )->getPass( 0 )->createTextureUnitState();
00082   tu->setTextureName( texture_.getTexture()->getName() );
00083   tu->setTextureFiltering( Ogre::TFO_NONE );
00084   tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
00085   image_material_->setCullingMode( Ogre::CULL_NONE );
00086   image_material_->setSceneBlending( Ogre::SBT_REPLACE );
00087 
00088   // Create the rectangle object
00089   manual_object_ = scene_manager_->createManualObject();
00090   scene_node_->attachObject( manual_object_ );
00091   manual_object_->estimateVertexCount( 10 );
00092   manual_object_->begin( image_material_->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST );
00093 
00094   manual_object_->position( -1, -1, 0 );
00095   manual_object_->textureCoord( 0, 1 );
00096 
00097   manual_object_->position( -1, 1, 0 );
00098   manual_object_->textureCoord( .5, 1 );
00099 
00100   manual_object_->position( 1, 1, 0 );
00101   manual_object_->textureCoord( 1, 1 );
00102 
00103   manual_object_->position( 1, 1, 2 );
00104   manual_object_->textureCoord( 1, 0 );
00105 
00106   manual_object_->position( -1, 1, 2 );
00107   manual_object_->textureCoord( .5, 0 );
00108 
00109   manual_object_->position( -1, -1, 2 );
00110   manual_object_->textureCoord( 0, 0 );
00111 
00112   manual_object_->quad( 0, 1, 4, 5 );
00113   manual_object_->quad( 1, 2, 3, 4 );
00114 
00115   manual_object_->position( -1, -1, 0 );
00116   manual_object_->textureCoord( 0, .999 );
00117 
00118   manual_object_->position( 1, -1, 0 );
00119   manual_object_->textureCoord( 0, .999 );
00120 
00121   manual_object_->position( 1, 1, 0 );
00122   manual_object_->textureCoord( 0, .999 );
00123 
00124   manual_object_->position( -1, 1, 0 );
00125   manual_object_->textureCoord( 0, .999 );
00126 
00127   manual_object_->quad( 6, 7, 8, 9 );
00128 
00129   manual_object_->end();
00130 }
00131 
00132 BackdropDisplay::~BackdropDisplay()
00133 {
00134   unsubscribe();
00135 
00136   scene_manager_->destroySceneNode( scene_node_ );
00137   scene_manager_->destroyManualObject( manual_object_ );
00138   image_material_->unload();
00139 }
00140 
00141 void BackdropDisplay::setTopic( const std::string& topic )
00142 {
00143   unsubscribe();
00144   topic_ = topic;
00145   subscribe();
00146 
00147   // Broadcast the fact that the variable has changed.
00148   //Property::changed();
00149 
00150   // Make sure rviz renders the next time it gets a chance.
00151  // causeRender();
00152 }
00153 
00154 /* Hydro development removal 
00155 
00156 void BackdropDisplay::subscribe()
00157 {
00158   // If we are not actually enabled, don't do it.
00159   if ( !isEnabled() )
00160   {
00161     return;
00162   }
00163 
00164   try
00165   {
00166    // texture_.setTopic( topic_ );
00167    // setStatus( rviz::status_levels::Ok, "Topic", "OK" );
00168   }
00169   catch( ros::Exception& e )
00170   {
00171     //setStatus( rviz::status_levels::Error, "Topic", std::string("Error subscribing: ") + e.what() );
00172   }
00173 }
00174 
00175 */
00176 
00177 /* Hydro development removal 
00178 
00179 void BackdropDisplay::unsubscribe()
00180 {
00181   //texture_.setTopic( "" );
00182 }
00183 
00184 */
00185 
00186 void BackdropDisplay::onEnable()
00187 {
00188   subscribe();
00189   scene_node_->setVisible( true );
00190 }
00191 
00192 void BackdropDisplay::onDisable()
00193 {
00194   unsubscribe();
00195   scene_node_->setVisible( false );
00196 }
00197 
00198 void BackdropDisplay::update( float dt, float ros_dt )
00199 {
00200   if (!texture_.getImage())
00201   {
00202    // setStatus(rviz::status_levels::Warn, "Image", "No image received");
00203   }
00204   else
00205   {
00206     std::stringstream ss;
00207     //ss << texture_.getImageCount() << " images received";
00208  //   setStatus(rviz::status_levels::Ok, "Image", ss.str());
00209   }
00210 
00211   //texture_.update();
00212 
00213   sensor_msgs::Image::ConstPtr current_image = texture_.getImage();
00214   if( current_image )
00215   {
00216     scene_node_->setScale( scale_, scale_, scale_ * 2.0 * current_image->height / current_image->width );
00217 
00218     std::string image_frame = current_image->header.frame_id;
00219     if( image_frame == "" )
00220     {
00221     //  image_frame = fixed_frame_;
00222     //  setStatus(rviz::status_levels::Warn, "Frame", "Image header has empty frame_id.");
00223     }
00224 
00225     Ogre::Vector3 position;
00226     Ogre::Quaternion orientation;
00227     //if( vis_manager_->getFrameManager()->getTransform( image_frame, ros::Time(), position, orientation ))
00228     //{
00229     //  scene_node_->setPosition( position );
00230     //  scene_node_->setOrientation( orientation );
00231     //  setStatus( rviz::status_levels::Ok, "Frame", "Ok" );
00232     //}
00233   //  else
00234    // {
00235    //   setStatus( rviz::status_levels::Error,
00236    //              "Frame", "Can't find a transform from " + fixed_frame_ + " to " + image_frame + "." );
00237    // }
00238   }
00239 }
00240 
00241 void BackdropDisplay::setScale( float scale )
00242 {
00243   scale_ = scale;
00244   //changed( scale_property_ );
00245 }
00246 
00247 // Override createProperties() to build and configure a Property
00248 // object for each user-editable property.  ``property_manager_``,
00249 // ``property_prefix_``, and ``parent_category_`` are all initialized before
00250 // this is called.
00251 void BackdropDisplay::createProperties()
00252 {
00253   //topic_property_ =
00254   //  new rviz::RosTopicProperty( "Topic",
00255                                                                 //     property_prefix_,
00256             //                                                         boost::bind( &BackdropDisplay::getTopic, this ),
00257               //                                                       boost::bind( &BackdropDisplay::setTopic, this, _1 ),
00258                                      //                                "sensor_msgs::Image topic to //subscribe to.",//
00259                                                                  //    parent_category_,
00260                                 //                                     SLOT(updateAcc()),
00261                                  //                                    this );
00262 
00263   //DEPRECATED:Hydro//setPropertyHelpText( topic_property_, "sensor_msgs::Image topic to subscribe to." );
00264   //rviz::ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00265   //topic_prop->setMessageType( ros::message_traits::datatype<sensor_msgs::Image>() );
00266 
00267   //scale_property_ =
00268   //  new rviz::FloatProperty( "Scale",
00269                                                          //   property_prefix_,
00270                               //                              "Scale of image, in meters per pixel",
00271                                                             //boost::bind( &BackdropDisplay::getScale, this ),
00272                                                             //boost::bind( &BackdropDisplay::setScale, this, _1 ),                                                          
00273       //                                                      SLOT(updateAcc()),
00274                                                          //   parent_category_,
00275         //                                                    this );
00276   //DEPRECATED:Hydro//setPropertyHelpText( scale_property_, "Scale of image, in meters per pixel." );
00277 }
00278 
00279 } // end namespace rviz_backdrop
00280 
00281 // Tell pluginlib about this class.  It is important to do this in
00282 // global scope, outside our package's namespace.
00283 #include <pluginlib/class_list_macros.h>
00284 PLUGINLIB_DECLARE_CLASS( rviz_backdrop, Backdrop, rviz_backdrop::BackdropDisplay, rviz::Display )
00285 // END_TUTORIAL


rviz_backdrop
Author(s): Dave Hershberger
autogenerated on Thu Jun 6 2019 20:32:07