map_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, 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 <boost/bind.hpp>
00031 
00032 #include <OGRE/OgreManualObject.h>
00033 #include <OGRE/OgreMaterialManager.h>
00034 #include <OGRE/OgreSceneManager.h>
00035 #include <OGRE/OgreSceneNode.h>
00036 #include <OGRE/OgreTextureManager.h>
00037 
00038 #include <ros/ros.h>
00039 
00040 #include <tf/transform_listener.h>
00041 
00042 #include "rviz/frame_manager.h"
00043 #include "rviz/ogre_helpers/grid.h"
00044 #include "rviz/properties/float_property.h"
00045 #include "rviz/properties/int_property.h"
00046 #include "rviz/properties/property.h"
00047 #include "rviz/properties/quaternion_property.h"
00048 #include "rviz/properties/ros_topic_property.h"
00049 #include "rviz/properties/vector_property.h"
00050 #include "rviz/validate_floats.h"
00051 #include "rviz/display_context.h"
00052 
00053 #include "map_display.h"
00054 
00055 namespace rviz
00056 {
00057 
00058 MapDisplay::MapDisplay()
00059   : Display()
00060   , manual_object_( NULL )
00061   , material_( 0 )
00062   , loaded_( false )
00063   , resolution_( 0.0f )
00064   , width_( 0 )
00065   , height_( 0 )
00066   , position_(Ogre::Vector3::ZERO)
00067   , orientation_(Ogre::Quaternion::IDENTITY)
00068   , new_map_(false)
00069 {
00070   topic_property_ = new RosTopicProperty( "Topic", "",
00071                                           QString::fromStdString( ros::message_traits::datatype<nav_msgs::OccupancyGrid>() ),
00072                                           "nav_msgs::OccupancyGrid topic to subscribe to.",
00073                                           this, SLOT( updateTopic() ));
00074 
00075   alpha_property_ = new FloatProperty( "Alpha", 0.7,
00076                                        "Amount of transparency to apply to the map.",
00077                                        this, SLOT( updateAlpha() ));
00078   alpha_property_->setMin( 0 );
00079   alpha_property_->setMax( 1 );
00080 
00081   draw_under_property_ = new Property( "Draw Behind", false,
00082                                        "Rendering option, controls whether or not the map is always"
00083                                        " drawn behind everything else.",
00084                                        this, SLOT( updateDrawUnder() ));
00085 
00086   resolution_property_ = new FloatProperty( "Resolution", 0,
00087                                             "Resolution of the map. (not editable)", this );
00088   resolution_property_->setReadOnly( true );
00089 
00090   width_property_ = new IntProperty( "Width", 0,
00091                                      "Width of the map, in meters. (not editable)", this );
00092   width_property_->setReadOnly( true );
00093   
00094   height_property_ = new IntProperty( "Height", 0,
00095                                       "Height of the map, in meters. (not editable)", this );
00096   height_property_->setReadOnly( true );
00097 
00098   position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO,
00099                                            "Position of the bottom left corner of the map, in meters. (not editable)",
00100                                            this );
00101   position_property_->setReadOnly( true );
00102 
00103   orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY,
00104                                                   "Orientation of the map. (not editable)",
00105                                                   this );
00106   orientation_property_->setReadOnly( true );
00107 }
00108 
00109 MapDisplay::~MapDisplay()
00110 {
00111   unsubscribe();
00112   clear();
00113 }
00114 
00115 void MapDisplay::onInitialize()
00116 {
00117   static int count = 0;
00118   std::stringstream ss;
00119   ss << "MapObjectMaterial" << count++;
00120   material_ = Ogre::MaterialManager::getSingleton().create( ss.str(),
00121                                                             Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00122   material_->setReceiveShadows(false);
00123   material_->getTechnique(0)->setLightingEnabled(false);
00124   material_->setDepthBias( -16.0f, 0.0f );
00125   material_->setCullingMode( Ogre::CULL_NONE );
00126   material_->setDepthWriteEnabled(false);
00127 
00128   updateAlpha();
00129 }
00130 
00131 void MapDisplay::onEnable()
00132 {
00133   subscribe();
00134 }
00135 
00136 void MapDisplay::onDisable()
00137 {
00138   unsubscribe();
00139   clear();
00140 }
00141 
00142 void MapDisplay::subscribe()
00143 {
00144   if ( !isEnabled() )
00145   {
00146     return;
00147   }
00148 
00149   if( !topic_property_->getTopic().isEmpty() )
00150   {
00151     try
00152     {
00153       map_sub_ = update_nh_.subscribe( topic_property_->getTopicStd(), 1, &MapDisplay::incomingMap, this );
00154       setStatus( StatusProperty::Ok, "Topic", "OK" );
00155     }
00156     catch( ros::Exception& e )
00157     {
00158       setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
00159     }
00160   }
00161 }
00162 
00163 void MapDisplay::unsubscribe()
00164 {
00165   map_sub_.shutdown();
00166 }
00167 
00168 void MapDisplay::updateAlpha()
00169 {
00170   float alpha = alpha_property_->getFloat();
00171 
00172   Ogre::Pass* pass = material_->getTechnique( 0 )->getPass( 0 );
00173   Ogre::TextureUnitState* tex_unit = NULL;
00174   if( pass->getNumTextureUnitStates() > 0 )
00175   {
00176     tex_unit = pass->getTextureUnitState( 0 );
00177   }
00178   else
00179   {
00180     tex_unit = pass->createTextureUnitState();
00181   }
00182 
00183   tex_unit->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
00184 
00185   if( alpha < 0.9998 )
00186   {
00187     material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00188     material_->setDepthWriteEnabled( false );
00189   }
00190   else
00191   {
00192     material_->setSceneBlending( Ogre::SBT_REPLACE );
00193     material_->setDepthWriteEnabled( !draw_under_property_->getValue().toBool() );
00194   }
00195 }
00196 
00197 void MapDisplay::updateDrawUnder()
00198 {
00199   bool draw_under = draw_under_property_->getValue().toBool();
00200 
00201   if( alpha_property_->getFloat() >= 0.9998 )
00202   {
00203     material_->setDepthWriteEnabled( !draw_under );
00204   }
00205 
00206   if( manual_object_ )
00207   {
00208     if( draw_under )
00209     {
00210       manual_object_->setRenderQueueGroup( Ogre::RENDER_QUEUE_4 );
00211     }
00212     else
00213     {
00214       manual_object_->setRenderQueueGroup( Ogre::RENDER_QUEUE_MAIN );
00215     }
00216   }
00217 }
00218 
00219 void MapDisplay::updateTopic()
00220 {
00221   unsubscribe();
00222   subscribe();
00223   clear();
00224 }
00225 
00226 void MapDisplay::clear()
00227 {
00228   setStatus( StatusProperty::Warn, "Message", "No map received" );
00229 
00230   if( !loaded_ )
00231   {
00232     return;
00233   }
00234 
00235   scene_manager_->destroyManualObject( manual_object_ );
00236   manual_object_ = NULL;
00237 
00238   std::string tex_name = texture_->getName();
00239   texture_.setNull();
00240   Ogre::TextureManager::getSingleton().unload( tex_name );
00241 
00242   loaded_ = false;
00243 }
00244 
00245 bool validateFloats(const nav_msgs::OccupancyGrid& msg)
00246 {
00247   bool valid = true;
00248   valid = valid && validateFloats( msg.info.resolution );
00249   valid = valid && validateFloats( msg.info.origin );
00250   return valid;
00251 }
00252 
00253 void MapDisplay::update( float wall_dt, float ros_dt )
00254 {
00255   {
00256     boost::mutex::scoped_lock lock(mutex_);
00257 
00258     current_map_ = updated_map_;
00259   }
00260 
00261   if (!current_map_ || !new_map_)
00262   {
00263     return;
00264   }
00265 
00266   if (current_map_->data.empty())
00267   {
00268     return;
00269   }
00270 
00271   new_map_ = false;
00272 
00273   if( !validateFloats( *current_map_ ))
00274   {
00275     setStatus( StatusProperty::Error, "Map", "Message contained invalid floating point values (nans or infs)" );
00276     return;
00277   }
00278 
00279   if( current_map_->info.width * current_map_->info.height == 0 )
00280   {
00281     std::stringstream ss;
00282     ss << "Map is zero-sized (" << current_map_->info.width << "x" << current_map_->info.height << ")";
00283     setStatus( StatusProperty::Error, "Map", QString::fromStdString( ss.str() ));
00284     return;
00285   }
00286 
00287   clear();
00288 
00289   setStatus( StatusProperty::Ok, "Message", "Map received" );
00290 
00291   ROS_DEBUG( "Received a %d X %d map @ %.3f m/pix\n",
00292              current_map_->info.width,
00293              current_map_->info.height,
00294              current_map_->info.resolution );
00295 
00296   float resolution = current_map_->info.resolution;
00297 
00298   int width = current_map_->info.width;
00299   int height = current_map_->info.height;
00300 
00301 
00302   Ogre::Vector3 position( current_map_->info.origin.position.x,
00303                           current_map_->info.origin.position.y,
00304                           current_map_->info.origin.position.z );
00305   Ogre::Quaternion orientation( current_map_->info.origin.orientation.w,
00306                                 current_map_->info.origin.orientation.x,
00307                                 current_map_->info.origin.orientation.y,
00308                                 current_map_->info.origin.orientation.z );
00309   frame_ = current_map_->header.frame_id;
00310   if (frame_.empty())
00311   {
00312     frame_ = "/map";
00313   }
00314 
00315   // Expand it to be RGB data
00316   unsigned int pixels_size = width * height;
00317   unsigned char* pixels = new unsigned char[pixels_size];
00318   memset(pixels, 255, pixels_size);
00319 
00320   bool map_status_set = false;
00321   unsigned int num_pixels_to_copy = pixels_size;
00322   if( pixels_size != current_map_->data.size() )
00323   {
00324     std::stringstream ss;
00325     ss << "Data size doesn't match width*height: width = " << width
00326        << ", height = " << height << ", data size = " << current_map_->data.size();
00327     setStatus( StatusProperty::Error, "Map", QString::fromStdString( ss.str() ));
00328     map_status_set = true;
00329 
00330     // Keep going, but don't read past the end of the data.
00331     if( current_map_->data.size() < pixels_size )
00332     {
00333       num_pixels_to_copy = current_map_->data.size();
00334     }
00335   }
00336 
00337   // TODO: a fragment shader could do this on the video card, and
00338   // would allow a non-grayscale color to mark the out-of-range
00339   // values.
00340   for( unsigned int pixel_index = 0; pixel_index < num_pixels_to_copy; pixel_index++ )
00341   {
00342     unsigned char val;
00343     int8_t data = current_map_->data[ pixel_index ];
00344     if( data > 100 )
00345       val = 127;
00346     else if( data < 0 )
00347       val = 127;
00348     else
00349       val = int8_t((int(100 - data) * 255) / 100);
00350 
00351     pixels[ pixel_index ] = val;
00352   }
00353 
00354   Ogre::DataStreamPtr pixel_stream;
00355   pixel_stream.bind( new Ogre::MemoryDataStream( pixels, pixels_size ));
00356   static int tex_count = 0;
00357   std::stringstream ss;
00358   ss << "MapTexture" << tex_count++;
00359   try
00360   {
00361     texture_ = Ogre::TextureManager::getSingleton().loadRawData( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00362                                                                  pixel_stream, width, height, Ogre::PF_L8, Ogre::TEX_TYPE_2D,
00363                                                                  0);
00364 
00365     if( !map_status_set )
00366     {
00367       setStatus( StatusProperty::Ok, "Map", "Map OK" );
00368     }
00369   }
00370   catch(Ogre::RenderingAPIException&)
00371   {
00372     Ogre::Image image;
00373     pixel_stream->seek(0);
00374     float fwidth = width;
00375     float fheight = height;
00376     if( width > height )
00377     {
00378       float aspect = fheight / fwidth;
00379       fwidth = 2048;
00380       fheight = fwidth * aspect;
00381     }
00382     else
00383     {
00384       float aspect = fwidth / fheight;
00385       fheight = 2048;
00386       fwidth = fheight * aspect;
00387     }
00388 
00389     {
00390       std::stringstream ss;
00391       ss << "Map is larger than your graphics card supports.  Downsampled from [" << width << "x" << height << "] to [" << fwidth << "x" << fheight << "]";
00392       setStatus(StatusProperty::Ok, "Map", QString::fromStdString( ss.str() ));
00393     }
00394 
00395     ROS_WARN("Failed to create full-size map texture, likely because your graphics card does not support textures of size > 2048.  Downsampling to [%d x %d]...", (int)fwidth, (int)fheight);
00396     //ROS_INFO("Stream size [%d], width [%f], height [%f], w * h [%f]", pixel_stream->size(), width, height, width * height);
00397     image.loadRawData(pixel_stream, width, height, Ogre::PF_L8);
00398     image.resize(fwidth, fheight, Ogre::Image::FILTER_NEAREST);
00399     ss << "Downsampled";
00400     texture_ = Ogre::TextureManager::getSingleton().loadImage(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
00401   }
00402 
00403   delete [] pixels;
00404 
00405   Ogre::Pass* pass = material_->getTechnique(0)->getPass(0);
00406   Ogre::TextureUnitState* tex_unit = NULL;
00407   if (pass->getNumTextureUnitStates() > 0)
00408   {
00409     tex_unit = pass->getTextureUnitState(0);
00410   }
00411   else
00412   {
00413     tex_unit = pass->createTextureUnitState();
00414   }
00415 
00416   tex_unit->setTextureName(texture_->getName());
00417   tex_unit->setTextureFiltering( Ogre::TFO_NONE );
00418 
00419   static int map_count = 0;
00420   std::stringstream ss2;
00421   ss2 << "MapObject" << map_count++;
00422   manual_object_ = scene_manager_->createManualObject( ss2.str() );
00423   scene_node_->attachObject( manual_object_ );
00424 
00425   manual_object_->begin(material_->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
00426   {
00427     // First triangle
00428     {
00429       // Bottom left
00430       manual_object_->position( 0.0f, 0.0f, 0.0f );
00431       manual_object_->textureCoord(0.0f, 0.0f);
00432       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00433 
00434       // Top right
00435       manual_object_->position( resolution*width, resolution*height, 0.0f );
00436       manual_object_->textureCoord(1.0f, 1.0f);
00437       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00438 
00439       // Top left
00440       manual_object_->position( 0.0f, resolution*height, 0.0f );
00441       manual_object_->textureCoord(0.0f, 1.0f);
00442       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00443     }
00444 
00445     // Second triangle
00446     {
00447       // Bottom left
00448       manual_object_->position( 0.0f, 0.0f, 0.0f );
00449       manual_object_->textureCoord(0.0f, 0.0f);
00450       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00451 
00452       // Bottom right
00453       manual_object_->position( resolution*width, 0.0f, 0.0f );
00454       manual_object_->textureCoord(1.0f, 0.0f);
00455       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00456 
00457       // Top right
00458       manual_object_->position( resolution*width, resolution*height, 0.0f );
00459       manual_object_->textureCoord(1.0f, 1.0f);
00460       manual_object_->normal( 0.0f, 0.0f, 1.0f );
00461     }
00462   }
00463   manual_object_->end();
00464 
00465   if( draw_under_property_->getValue().toBool() )
00466   {
00467     manual_object_->setRenderQueueGroup(Ogre::RENDER_QUEUE_4);
00468   }
00469 
00470   resolution_property_->setValue( resolution );
00471   width_property_->setValue( width );
00472   height_property_->setValue( height );
00473   position_property_->setVector( position );
00474   orientation_property_->setQuaternion( orientation );
00475 
00476   transformMap();
00477 
00478   loaded_ = true;
00479 
00480   context_->queueRender();
00481 }
00482 
00483 void MapDisplay::incomingMap(const nav_msgs::OccupancyGrid::ConstPtr& msg)
00484 {
00485 
00486   updated_map_ = msg;
00487   boost::mutex::scoped_lock lock(mutex_);
00488   new_map_ = true;
00489 }
00490 
00491 
00492 
00493 void MapDisplay::transformMap()
00494 {
00495   if (!current_map_)
00496   {
00497     return;
00498   }
00499 
00500   Ogre::Vector3 position;
00501   Ogre::Quaternion orientation;
00502   if (!context_->getFrameManager()->transform(frame_, ros::Time(), current_map_->info.origin, position, orientation))
00503   {
00504     ROS_DEBUG( "Error transforming map '%s' from frame '%s' to frame '%s'",
00505                qPrintable( getName() ), frame_.c_str(), qPrintable( fixed_frame_ ));
00506 
00507     setStatus( StatusProperty::Error, "Transform",
00508                "No transform from [" + QString::fromStdString( frame_ ) + "] to [" + fixed_frame_ + "]" );
00509   }
00510   else
00511   {
00512     setStatus(StatusProperty::Ok, "Transform", "Transform OK");
00513   }
00514 
00515   scene_node_->setPosition( position );
00516   scene_node_->setOrientation( orientation );
00517 }
00518 
00519 void MapDisplay::fixedFrameChanged()
00520 {
00521   transformMap();
00522 }
00523 
00524 void MapDisplay::reset()
00525 {
00526   Display::reset();
00527 
00528   clear();
00529   // Force resubscription so that the map will be re-sent
00530   updateTopic();
00531 }
00532 
00533 } // namespace rviz
00534 
00535 #include <pluginlib/class_list_macros.h>
00536 PLUGINLIB_EXPORT_CLASS( rviz::MapDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35