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