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