00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include <algorithm>
00012 #include <assert.h>
00013 #include <utility>
00014 #include <sstream>
00015
00016 #include <gazebo_plugins/gazebo_ros_projector.h>
00017
00018 #include <gazebo/OgreAdaptor.hh>
00019 #include <gazebo/OgreVisual.hh>
00020 #include <gazebo/Sensor.hh>
00021 #include <gazebo/Global.hh>
00022 #include <gazebo/XMLConfig.hh>
00023 #include <gazebo/Simulator.hh>
00024 #include <gazebo/gazebo.h>
00025 #include <gazebo/World.hh>
00026 #include <gazebo/GazeboError.hh>
00027 #include <gazebo/ControllerFactory.hh>
00028
00029 #include "std_msgs/String.h"
00030 #include "std_msgs/Int32.h"
00031
00032 #include <Ogre.h>
00033 #include <OgreMath.h>
00034 #include <OgreSceneNode.h>
00035 #include <OgreFrustum.h>
00036 #include <OgreSceneQuery.h>
00037
00038 using namespace gazebo;
00039
00040 typedef std::map<std::string,Ogre::Pass*> OgrePassMap;
00041 typedef OgrePassMap::iterator OgrePassMapIterator;
00042
00043 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_projector", GazeboRosProjector);
00044
00046
00047 GazeboRosProjector::GazeboRosProjector(Entity *parent)
00048 : Controller(parent)
00049 {
00050 this->myParent = dynamic_cast<Model*>(this->parent);
00051 if (!this->myParent)
00052 gzthrow("GazeboRosProjector controller requires a Model as its parent");
00053
00054 Param::Begin(&this->parameters);
00055 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0);
00056 this->textureTopicNameP = new ParamT<std::string>("textureTopicName","", 1);
00057 this->projectorTopicNameP = new ParamT<std::string>("projectorTopicName","", 1);
00058 this->bodyNameP = new ParamT<std::string>("bodyName","", 0);
00059 this->textureNameP = new ParamT<std::string>("textureName","", 0);
00060 this->filterTextureNameP = new ParamT<std::string>("filterTextureName","", 0);
00061 this->nearClipDistP = new ParamT<double>("nearClipDist", .1, 0);
00062 this->farClipDistP = new ParamT<double>("farClipDist", 15, 0);
00063 this->fovP = new ParamT<double>("fov", Ogre::Math::PI*.25, 0);
00064 Param::End();
00065
00066 this->fov = Ogre::Math::PI*.25;
00067 this->nearClipDist = .25;
00068 this->farClipDist = 15;
00069
00070 this->rosnode_ = NULL;
00071
00072 std::ostringstream fn_stream;
00073 fn_stream << this->myParent->GetName() << "_FilterNode";
00074 this->filterNodeName = fn_stream.str();
00075 }
00076
00078
00079 GazeboRosProjector::~GazeboRosProjector()
00080 {
00081 delete this->robotNamespaceP;
00082 delete this->rosnode_;
00083
00084 delete this->textureTopicNameP;
00085 delete this->projectorTopicNameP;
00086 delete this->bodyNameP;
00087 delete this->textureNameP;
00088 delete this->filterTextureNameP;
00089 delete this->fovP;
00090 delete this->nearClipDistP;
00091 delete this->farClipDistP;
00092
00093 }
00094
00096
00097 void GazeboRosProjector::LoadChild(XMLConfigNode *node)
00098 {
00099 this->robotNamespaceP->Load(node);
00100 this->robotNamespace = this->robotNamespaceP->GetValue();
00101
00102 if (!ros::isInitialized())
00103 {
00104 int argc = 0;
00105 char** argv = NULL;
00106 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName);
00107 }
00108
00109 this->rosnode_ = new ros::NodeHandle(this->robotNamespace);
00110
00111 this->textureTopicNameP->Load(node);
00112 this->projectorTopicNameP->Load(node);
00113 this->bodyNameP->Load(node);
00114 this->textureNameP->Load(node);
00115 this->filterTextureNameP->Load(node);
00116 this->fovP->Load(node);
00117 this->nearClipDistP->Load(node);
00118 this->farClipDistP->Load(node);
00119
00120 this->textureTopicName = this->textureTopicNameP->GetValue();
00121 this->projectorTopicName = this->projectorTopicNameP->GetValue();
00122 this->bodyName = this->bodyNameP->GetValue();
00123 this->textureName = this->textureNameP->GetValue();
00124 this->filterTextureName = this->filterTextureNameP->GetValue();
00125 this->fov = this->fovP->GetValue();
00126 this->nearClipDist = this->nearClipDistP->GetValue();
00127 this->farClipDist = this->farClipDistP->GetValue();
00128
00129
00130 this->myBody = dynamic_cast<Body*>(this->myParent->GetBody(this->bodyName));
00131 if (this->myBody == NULL)
00132 {
00133 ROS_WARN("gazebo_ros_projector plugin error: bodyName: %s does not exist\n",this->bodyName.c_str());
00134 return;
00135 }
00136
00137
00138 ros::SubscribeOptions so = ros::SubscribeOptions::create<std_msgs::Int32>(
00139 this->projectorTopicName,1,
00140 boost::bind( &GazeboRosProjector::ToggleProjector,this,_1),
00141 ros::VoidPtr(), &this->queue_);
00142 this->projectorSubscriber_ = this->rosnode_->subscribe(so);
00143
00144 ros::SubscribeOptions so2 = ros::SubscribeOptions::create<std_msgs::String>(
00145 this->textureTopicName,1,
00146 boost::bind( &GazeboRosProjector::LoadImage,this,_1),
00147 ros::VoidPtr(), &this->queue_);
00148 this->imageSubscriber_ = this->rosnode_->subscribe(so2);
00149 }
00150
00152
00153 void GazeboRosProjector::InitChild()
00154 {
00155
00156 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosProjector::QueueThread,this ) );
00157
00158
00159 if (Simulator::Instance()->GetRenderEngineEnabled())
00160 {
00161 projector_.init( this->myBody->GetVisualNode()->GetSceneNode(),
00162 this->textureName, this->filterTextureName,
00163 this->nearClipDist, this->farClipDist, this->fov, this->filterNodeName );
00164
00165
00166 getRootP()->addFrameListener( &this->projector_ );
00167 }
00168 }
00169
00171
00172 void GazeboRosProjector::LoadImage(const std_msgs::String::ConstPtr& imageMsg)
00173 {
00174 if (Simulator::Instance()->GetRenderEngineEnabled())
00175 {
00176 this->lock.lock();
00177 this->projector_.setTextureName( imageMsg->data );
00178 this->lock.unlock();
00179 }
00180 }
00181
00183
00184 void GazeboRosProjector::ToggleProjector(const std_msgs::Int32::ConstPtr& projectorMsg)
00185 {
00186 if (Simulator::Instance()->GetRenderEngineEnabled())
00187 {
00188 this->lock.lock();
00189 this->projector_.setEnabled( projectorMsg->data ? true : false );
00190 this->lock.unlock();
00191 }
00192 }
00193
00195
00196 void GazeboRosProjector::UpdateChild()
00197 {
00198
00199 }
00200
00202
00203 void GazeboRosProjector::FiniChild()
00204 {
00205
00206 this->queue_.clear();
00207 this->queue_.disable();
00208 this->rosnode_->shutdown();
00209 this->callback_queue_thread_.join();
00210
00211
00212 getRootP()->removeFrameListener( &this->projector_ );
00213 }
00214
00215 Ogre::Root* GazeboRosProjector::getRootP()
00216 {
00217 return Ogre::Root::getSingletonPtr();
00218 }
00219
00221
00222 void GazeboRosProjector::QueueThread()
00223 {
00224 static const double timeout = 0.01;
00225
00226 while (this->rosnode_->ok())
00227 {
00228 this->queue_.callAvailable(ros::WallDuration(timeout));
00229 }
00230 }
00231
00233 GazeboRosProjector::Projector::Projector()
00234 {
00235 this->isEnabled = false;
00236 this->isInit = false;
00237 this->isUsingShaders = false;
00238
00239 this->projectorNode = NULL;
00240 this->projectorFilterNode = NULL;
00241 this->projectorQuery = NULL;
00242 this->projectorFrustum = NULL;
00243 this->projectorFilterFrustum = NULL;
00244
00245 this->filterNodeName = "FilterNode";
00246 }
00247
00249 GazeboRosProjector::Projector::~Projector()
00250 {
00251 removeProjectorPassFromMaterials();
00252
00253 if( this->projectorNode )
00254 {
00255 this->projectorNode->detachObject( this->projectorFrustum );
00256 this->projectorFilterNode->detachObject( this->projectorFilterFrustum );
00257 this->projectorNode->removeAndDestroyChild(this->filterNodeName);
00258 }
00259
00260 delete this->projectorFrustum;
00261 delete this->projectorFilterFrustum;
00262
00263 if( this->projectorQuery )
00264 getSceneMgrP()->destroyQuery( this->projectorQuery );
00265 }
00266
00267 void GazeboRosProjector::Projector::init( Ogre::SceneNode *sceneNodePtr,
00268 Ogre::String textureName,
00269 Ogre::String filterTextureName,
00270 double nearDist,
00271 double farDist,
00272 double fov,
00273 std::string filterNodeName )
00274 {
00275 if( this->isInit )
00276 return;
00277
00278 this->filterNodeName = filterNodeName;
00279
00280 this->projectorFrustum = new Ogre::Frustum();
00281 this->projectorFilterFrustum = new Ogre::Frustum();
00282 this->projectorFilterFrustum->setProjectionType(Ogre::PT_ORTHOGRAPHIC);
00283
00284 this->projectorQuery = getSceneMgrP()->createPlaneBoundedVolumeQuery(Ogre::PlaneBoundedVolumeList());
00285
00286 setSceneNode( sceneNodePtr );
00287 setTextureName( textureName );
00288 setFilterTextureName( filterTextureName );
00289 setFrustumClipDistance( nearDist, farDist );
00290 setFrustumFOV( fov );
00291
00292 this->isInit = true;
00293 }
00294
00295
00297 bool GazeboRosProjector::Projector::frameStarted(const Ogre::FrameEvent &evt)
00298 {
00299 if( !isInit )
00300 init( this->projectorNode );
00301
00302 if( isEnabled && !projectedTextureName.empty() )
00303 {
00304 addProjectorPassToVisibleMaterials();
00305
00306 }
00307 else
00308 {
00309 removeProjectorPassFromMaterials();
00310 }
00311
00312 return true;
00313 }
00314
00316 bool GazeboRosProjector::Projector::frameEnded(const Ogre::FrameEvent &evt)
00317 {
00318 return true;
00319 }
00320
00322 bool GazeboRosProjector::Projector::frameRenderingQueued(const Ogre::FrameEvent &evt)
00323 {
00324 return true;
00325 }
00326
00328 void GazeboRosProjector::Projector::setEnabled(bool enabled)
00329 {
00330 this->isEnabled = enabled;
00331 }
00332
00334 void GazeboRosProjector::Projector::setUsingShaders(bool usingShaders)
00335 {
00336 this->isUsingShaders = usingShaders;
00337 }
00338
00340 void GazeboRosProjector::Projector::setSceneNode( Ogre::SceneNode *sceneNodePtr )
00341 {
00342 if( this->projectorNode )
00343 {
00344 this->projectorNode->detachObject( this->projectorFrustum );
00345 this->projectorFilterNode->detachObject( this->projectorFilterFrustum );
00346 this->projectorNode->removeAndDestroyChild(this->filterNodeName);
00347 this->projectorFilterNode = NULL;
00348 }
00349
00350 this->projectorNode = sceneNodePtr;
00351
00352 if( this->projectorNode )
00353 {
00354 this->projectorNode->attachObject( this->projectorFrustum );
00355 this->projectorFilterNode = sceneNodePtr->createChildSceneNode(this->filterNodeName);
00356 this->projectorFilterNode->attachObject( this->projectorFilterFrustum );
00357 this->projectorFilterNode->setOrientation( Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Y) );
00358 }
00359 }
00360
00362 void GazeboRosProjector::Projector::setTextureName( const Ogre::String& textureName )
00363 {
00364 this->projectedTextureName = textureName;
00365 }
00366
00368 void GazeboRosProjector::Projector::setFilterTextureName( const Ogre::String& textureName )
00369 {
00370 this->projectedFilterTextureName = textureName;
00371 }
00372
00374 void GazeboRosProjector::Projector::setFrustumClipDistance( double nearDist, double farDist )
00375 {
00376 this->projectorFrustum->setNearClipDistance( nearDist );
00377 this->projectorFilterFrustum->setNearClipDistance( nearDist );
00378 this->projectorFrustum->setFarClipDistance( farDist );
00379 this->projectorFilterFrustum->setFarClipDistance( farDist );
00380 }
00381
00383 void GazeboRosProjector::Projector::setFrustumFOV( double fovInRadians )
00384 {
00385 this->projectorFrustum->setFOVy( Ogre::Radian( fovInRadians ) );
00386 this->projectorFilterFrustum->setFOVy( Ogre::Radian( fovInRadians ) );
00387 }
00388
00390 Ogre::SceneManager* GazeboRosProjector::Projector::getSceneMgrP()
00391 {
00392 return OgreAdaptor::Instance()->sceneMgr;
00393 }
00394
00396 void GazeboRosProjector::Projector::addProjectorPassToAllMaterials()
00397 {
00398 using namespace Ogre;
00399
00400 std::list<std::string> allMaterials;
00401
00402 SceneManager::MovableObjectIterator it = getSceneMgrP()->getMovableObjectIterator("Entity");
00403
00404 while( it.hasMoreElements() )
00405 {
00406 Ogre::Entity* entity = dynamic_cast<Ogre::Entity*>( it.getNext() );
00407 if(entity && entity->getName().find("ENTITY") != std::string::npos)
00408
00409 for(unsigned int i = 0; i < entity->getNumSubEntities(); i++)
00410 {
00411 allMaterials.push_back( entity->getSubEntity( i )->getMaterialName() );
00412 }
00413 }
00414
00415 addProjectorPassToMaterials( allMaterials );
00416 }
00417
00419 void GazeboRosProjector::Projector::addProjectorPassToVisibleMaterials()
00420 {
00421 using namespace Ogre;
00422
00423 PlaneBoundedVolumeList volumeList;
00424 volumeList.push_back( projectorFrustum->getPlaneBoundedVolume() );
00425
00426 this->projectorQuery->setVolumes( volumeList );
00427 SceneQueryResult result = this->projectorQuery->execute();
00428
00429 std::list<std::string> newVisibleMaterials;
00430
00431
00432 SceneQueryResultMovableList::iterator it;
00433 for(it = result.movables.begin(); it != result.movables.end(); ++it)
00434 {
00435 Ogre::Entity* entity = dynamic_cast<Ogre::Entity*>( *it );
00436 if(entity && entity->getName().find("ENTITY") != std::string::npos)
00437 {
00438 for(unsigned int i = 0; i < entity->getNumSubEntities(); i++)
00439 {
00440
00441 newVisibleMaterials.push_back( entity->getSubEntity( i )->getMaterialName() );
00442 }
00443 }
00444 }
00445
00446 addProjectorPassToMaterials( newVisibleMaterials );
00447 }
00448
00450 void GazeboRosProjector::Projector::addProjectorPassToMaterials( std::list<std::string>& matList )
00451 {
00452 matList.remove("");
00453 matList.unique();
00454
00455
00456
00457 OgrePassMapIterator used = projectorTargets.begin();
00458 while( used != projectorTargets.end() )
00459 {
00460 std::list<std::string>::iterator visibleMaterial = std::find(matList.begin(),matList.end(),used->first);
00461
00462
00463 if( visibleMaterial == matList.end() )
00464 {
00465 std::string invisibleMaterial = used->first;
00466 ++used;
00467 removeProjectorPassFromMaterial( invisibleMaterial );
00468 }
00469
00470 else
00471 {
00472 matList.remove( used->first );
00473 ++used;
00474 }
00475 }
00476
00477
00478 while( !matList.empty() )
00479 {
00480 addProjectorPassToMaterial( matList.front() );
00481 matList.erase( matList.begin() );
00482 }
00483 }
00484
00486 void GazeboRosProjector::Projector::addProjectorPassToMaterial( std::string matName )
00487 {
00488 if( projectorTargets.find( matName ) != projectorTargets.end() )
00489 {
00490 ROS_DEBUG("Adding a Material that already exists.");
00491 return;
00492 }
00493
00494 using namespace Ogre;
00495
00496 MaterialPtr mat = (MaterialPtr)MaterialManager::getSingleton().getByName( matName );
00497 Pass *pass = mat->getTechnique( 0 )->createPass();
00498
00499 if( isUsingShaders )
00500 {
00501 Matrix4 viewProj = projectorFrustum->getProjectionMatrix() * projectorFrustum->getViewMatrix();
00502 pass->setVertexProgram("GazeboWorlds/TexProjectionVP");
00503
00504 GpuProgramParametersSharedPtr vsParams = pass->getVertexProgramParameters();
00505 GpuProgramParametersSharedPtr psParams = pass->getFragmentProgramParameters();
00506
00507
00508
00509 vsParams->setNamedAutoConstant("worldMatrix",GpuProgramParameters::ACT_WORLD_MATRIX);
00510 vsParams->setNamedConstant("texProjMatrix", viewProj);
00511
00512 pass->setVertexProgramParameters(vsParams);
00513
00514 }
00515
00516 TextureUnitState *texState = pass->createTextureUnitState( projectedTextureName );
00517 texState->setProjectiveTexturing(true, projectorFrustum);
00518 texState->setTextureAddressingMode(TextureUnitState::TAM_BORDER);
00519 texState->setTextureFiltering(TFO_ANISOTROPIC);
00520 texState->setTextureBorderColour(ColourValue(0.0, 0.0, 0.0, 0.0));
00521 texState->setColourOperation(LBO_ALPHA_BLEND);
00522
00523 texState = pass->createTextureUnitState( projectedFilterTextureName );
00524 texState->setProjectiveTexturing(true, projectorFilterFrustum);
00525 texState->setTextureAddressingMode(TextureUnitState::TAM_CLAMP);
00526 texState->setTextureFiltering(TFO_NONE);
00527
00528 pass->setSceneBlending( SBT_TRANSPARENT_ALPHA );
00529 pass->setDepthBias( 1 );
00530 pass->setLightingEnabled( false );
00531
00532 this->projectorTargets[ matName ] = pass;
00533 }
00534
00536 void GazeboRosProjector::Projector::removeProjectorPassFromMaterials()
00537 {
00538 for( OgrePassMap::const_iterator it = this->projectorTargets.begin(); it != this->projectorTargets.end(); ++it )
00539 {
00540 it->second->getParent()->removePass( it->second->getIndex() );
00541 }
00542 this->projectorTargets.clear();
00543 }
00544
00546 void GazeboRosProjector::Projector::removeProjectorPassFromMaterial(std::string matName)
00547 {
00548 this->projectorTargets[ matName ]->getParent()->removePass( this->projectorTargets[matName]->getIndex() );
00549 this->projectorTargets.erase( this->projectorTargets.find( matName ) );
00550 }
00551