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 <boost/filesystem.hpp>
00031
00032 #include <OGRE/OgreEntity.h>
00033 #include <OGRE/OgreMaterial.h>
00034 #include <OGRE/OgreMaterialManager.h>
00035 #include <OGRE/OgreRibbonTrail.h>
00036 #include <OGRE/OgreSceneManager.h>
00037 #include <OGRE/OgreSceneNode.h>
00038 #include <OGRE/OgreSubEntity.h>
00039 #include <OGRE/OgreTextureManager.h>
00040
00041 #include <ros/console.h>
00042
00043 #include <resource_retriever/retriever.h>
00044
00045 #include <urdf_model/model.h>
00046 #include <urdf_model/link.h>
00047
00048 #include "rviz/mesh_loader.h"
00049 #include "rviz/ogre_helpers/axes.h"
00050 #include "rviz/ogre_helpers/object.h"
00051 #include "rviz/ogre_helpers/shape.h"
00052 #include "rviz/properties/float_property.h"
00053 #include "rviz/properties/bool_property.h"
00054 #include "rviz/properties/property.h"
00055 #include "rviz/properties/quaternion_property.h"
00056 #include "rviz/properties/vector_property.h"
00057 #include "rviz/robot/robot.h"
00058 #include "rviz/selection/selection_manager.h"
00059 #include "rviz/visualization_manager.h"
00060 #include "rviz/load_resource.h"
00061
00062 #include "rviz/robot/robot_link.h"
00063 #include "rviz/robot/robot_joint.h"
00064
00065 namespace fs=boost::filesystem;
00066
00067 namespace rviz
00068 {
00069
00070 class RobotLinkSelectionHandler : public SelectionHandler
00071 {
00072 public:
00073 RobotLinkSelectionHandler( RobotLink* link, DisplayContext* context );
00074 virtual ~RobotLinkSelectionHandler();
00075
00076 virtual void createProperties( const Picked& obj, Property* parent_property );
00077 virtual void updateProperties();
00078
00079 virtual void preRenderPass(uint32_t pass);
00080 virtual void postRenderPass(uint32_t pass);
00081
00082 private:
00083 RobotLink* link_;
00084 VectorProperty* position_property_;
00085 QuaternionProperty* orientation_property_;
00086 };
00087
00088 RobotLinkSelectionHandler::RobotLinkSelectionHandler( RobotLink* link, DisplayContext* context )
00089 : SelectionHandler( context )
00090 , link_( link )
00091 {
00092 }
00093
00094 RobotLinkSelectionHandler::~RobotLinkSelectionHandler()
00095 {
00096 }
00097
00098 void RobotLinkSelectionHandler::createProperties( const Picked& obj, Property* parent_property )
00099 {
00100 Property* group = new Property( "Link " + QString::fromStdString( link_->getName() ), QVariant(), "", parent_property );
00101 properties_.push_back( group );
00102
00103 position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO, "", group );
00104 position_property_->setReadOnly( true );
00105
00106 orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY, "", group );
00107 orientation_property_->setReadOnly( true );
00108
00109 group->expand();
00110 }
00111
00112 void RobotLinkSelectionHandler::updateProperties()
00113 {
00114 position_property_->setVector( link_->getPosition() );
00115 orientation_property_->setQuaternion( link_->getOrientation() );
00116 }
00117
00118
00119 void RobotLinkSelectionHandler::preRenderPass(uint32_t pass)
00120 {
00121 if (!link_->is_selectable_)
00122 {
00123 if( link_->visual_node_ )
00124 {
00125 link_->visual_node_->setVisible( false );
00126 }
00127 if( link_->collision_node_ )
00128 {
00129 link_->collision_node_->setVisible( false );
00130 }
00131 if( link_->trail_ )
00132 {
00133 link_->trail_->setVisible( false );
00134 }
00135 if( link_->axes_ )
00136 {
00137 link_->axes_->getSceneNode()->setVisible( false );
00138 }
00139 }
00140 }
00141
00142 void RobotLinkSelectionHandler::postRenderPass(uint32_t pass)
00143 {
00144 if (!link_->is_selectable_)
00145 {
00146 link_->updateVisibility();
00147 }
00148 }
00149
00150
00151 RobotLink::RobotLink( Robot* robot,
00152 const urdf::LinkConstPtr& link,
00153 const std::string& parent_joint_name,
00154 bool visual,
00155 bool collision)
00156 : robot_( robot )
00157 , scene_manager_( robot->getDisplayContext()->getSceneManager() )
00158 , context_( robot->getDisplayContext() )
00159 , name_( link->name )
00160 , parent_joint_name_( parent_joint_name )
00161 , visual_node_( NULL )
00162 , collision_node_( NULL )
00163 , trail_( NULL )
00164 , axes_( NULL )
00165 , material_alpha_( 1.0 )
00166 , robot_alpha_(1.0)
00167 , only_render_depth_(false)
00168 , using_color_( false )
00169 , is_selectable_( true )
00170 {
00171 link_property_ = new Property( link->name.c_str(), true, "", NULL, SLOT( updateVisibility() ), this );
00172 link_property_->setIcon( rviz::loadPixmap( "package://rviz/icons/classes/RobotLink.png" ) );
00173
00174 details_ = new Property( "Details", QVariant(), "", NULL);
00175
00176 alpha_property_ = new FloatProperty( "Alpha", 1,
00177 "Amount of transparency to apply to this link.",
00178 link_property_, SLOT( updateAlpha() ), this );
00179
00180 trail_property_ = new Property( "Show Trail", false,
00181 "Enable/disable a 2 meter \"ribbon\" which follows this link.",
00182 link_property_, SLOT( updateTrail() ), this );
00183
00184 axes_property_ = new Property( "Show Axes", false,
00185 "Enable/disable showing the axes of this link.",
00186 link_property_, SLOT( updateAxes() ), this );
00187
00188 position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO,
00189 "Position of this link, in the current Fixed Frame. (Not editable)",
00190 link_property_ );
00191 position_property_->setReadOnly( true );
00192
00193 orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY,
00194 "Orientation of this link, in the current Fixed Frame. (Not editable)",
00195 link_property_ );
00196 orientation_property_->setReadOnly( true );
00197
00198 link_property_->collapse();
00199
00200 visual_node_ = robot_->getVisualNode()->createChildSceneNode();
00201 collision_node_ = robot_->getCollisionNode()->createChildSceneNode();
00202
00203
00204 std::stringstream ss;
00205 static int count = 1;
00206 ss << "robot link color material " << count;
00207 color_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), ROS_PACKAGE_NAME );
00208 color_material_->setReceiveShadows(false);
00209 color_material_->getTechnique(0)->setLightingEnabled(true);
00210
00211
00212
00213 if ( visual )
00214 {
00215 createVisual( link );
00216 }
00217
00218 if ( collision )
00219 {
00220 createCollision( link );
00221 }
00222
00223 if (collision || visual)
00224 {
00225 createSelection();
00226 }
00227
00228
00229 std::stringstream desc;
00230 if (parent_joint_name_.empty())
00231 {
00232 desc << "Root Link <b>" << name_ << "</b>";
00233 }
00234 else
00235 {
00236 desc << "Link <b>" << name_ << "</b>";
00237 desc << " with parent joint <b>" << parent_joint_name_ << "</b>";
00238 }
00239
00240 if (link->child_joints.empty())
00241 {
00242 desc << " has no children.";
00243 }
00244 else
00245 {
00246 desc
00247 << " has "
00248 << link->child_joints.size();
00249
00250 if (link->child_joints.size() > 1)
00251 {
00252 desc << " child joints: ";
00253 }
00254 else
00255 {
00256 desc << " child joint: ";
00257 }
00258
00259 std::vector<boost::shared_ptr<urdf::Joint> >::const_iterator child_it = link->child_joints.begin();
00260 std::vector<boost::shared_ptr<urdf::Joint> >::const_iterator child_end = link->child_joints.end();
00261 for ( ; child_it != child_end ; ++child_it )
00262 {
00263 urdf::Joint *child_joint = child_it->get();
00264 if (child_joint && !child_joint->name.empty())
00265 {
00266 child_joint_names_.push_back(child_joint->name);
00267 desc << "<b>" << child_joint->name << "</b>" << ((child_it+1 == child_end) ? "." : ", ");
00268 }
00269 }
00270 }
00271 if (hasGeometry())
00272 {
00273 desc << " Check/uncheck to show/hide this link in the display.";
00274 if (visual_meshes_.empty())
00275 {
00276 desc << " This link has collision geometry but no visible geometry.";
00277 }
00278 else if (collision_meshes_.empty())
00279 {
00280 desc << " This link has visible geometry but no collision geometry.";
00281 }
00282 }
00283 else
00284 {
00285 desc << " This link has NO geometry.";
00286 }
00287
00288 link_property_->setDescription(desc.str().c_str());
00289
00290 if (!hasGeometry())
00291 {
00292 link_property_->setIcon( rviz::loadPixmap( "package://rviz/icons/classes/RobotLinkNoGeom.png" ) );
00293 alpha_property_->hide();
00294 link_property_->setValue(QVariant());
00295 }
00296 }
00297
00298 RobotLink::~RobotLink()
00299 {
00300 for( size_t i = 0; i < visual_meshes_.size(); i++ )
00301 {
00302 scene_manager_->destroyEntity( visual_meshes_[ i ]);
00303 }
00304
00305 for( size_t i = 0; i < collision_meshes_.size(); i++ )
00306 {
00307 scene_manager_->destroyEntity( collision_meshes_[ i ]);
00308 }
00309
00310 scene_manager_->destroySceneNode( visual_node_ );
00311 scene_manager_->destroySceneNode( collision_node_ );
00312
00313 if ( trail_ )
00314 {
00315 scene_manager_->destroyRibbonTrail( trail_ );
00316 }
00317
00318 delete axes_;
00319 delete details_;
00320 delete link_property_;
00321 }
00322
00323 bool RobotLink::hasGeometry() const
00324 {
00325 return visual_meshes_.size() + collision_meshes_.size() > 0;
00326 }
00327
00328 bool RobotLink::getEnabled() const
00329 {
00330 if (!hasGeometry())
00331 return true;
00332 return link_property_->getValue().toBool();
00333 }
00334
00335 void RobotLink::setRobotAlpha( float a )
00336 {
00337 robot_alpha_ = a;
00338 updateAlpha();
00339 }
00340
00341 void RobotLink::setRenderQueueGroup( Ogre::uint8 group )
00342 {
00343 Ogre::SceneNode::ChildNodeIterator child_it = visual_node_->getChildIterator();
00344 while( child_it.hasMoreElements() )
00345 {
00346 Ogre::SceneNode* child = dynamic_cast<Ogre::SceneNode*>( child_it.getNext() );
00347 if( child )
00348 {
00349 Ogre::SceneNode::ObjectIterator object_it = child->getAttachedObjectIterator();
00350 while( object_it.hasMoreElements() )
00351 {
00352 Ogre::MovableObject* obj = object_it.getNext();
00353 obj->setRenderQueueGroup(group);
00354 }
00355 }
00356 }
00357 }
00358
00359 void RobotLink::setOnlyRenderDepth(bool onlyRenderDepth)
00360 {
00361 setRenderQueueGroup( onlyRenderDepth ? Ogre::RENDER_QUEUE_BACKGROUND : Ogre::RENDER_QUEUE_MAIN );
00362 only_render_depth_ = onlyRenderDepth;
00363 updateAlpha();
00364 }
00365
00366 void RobotLink::updateAlpha()
00367 {
00368 float link_alpha = alpha_property_->getFloat();
00369 M_SubEntityToMaterial::iterator it = materials_.begin();
00370 M_SubEntityToMaterial::iterator end = materials_.end();
00371 for (; it != end; ++it)
00372 {
00373 const Ogre::MaterialPtr& material = it->second;
00374
00375 if ( only_render_depth_ )
00376 {
00377 material->setColourWriteEnabled( false );
00378 material->setDepthWriteEnabled( true );
00379 }
00380 else
00381 {
00382 Ogre::ColourValue color = material->getTechnique(0)->getPass(0)->getDiffuse();
00383 color.a = robot_alpha_ * material_alpha_ * link_alpha;
00384 material->setDiffuse( color );
00385
00386 if ( color.a < 0.9998 )
00387 {
00388 material->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00389 material->setDepthWriteEnabled( false );
00390 }
00391 else
00392 {
00393 material->setSceneBlending( Ogre::SBT_REPLACE );
00394 material->setDepthWriteEnabled( true );
00395 }
00396 }
00397 }
00398
00399 Ogre::ColourValue color = color_material_->getTechnique(0)->getPass(0)->getDiffuse();
00400 color.a = robot_alpha_ * link_alpha;
00401 color_material_->setDiffuse( color );
00402
00403 if ( color.a < 0.9998 )
00404 {
00405 color_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00406 color_material_->setDepthWriteEnabled( false );
00407 }
00408 else
00409 {
00410 color_material_->setSceneBlending( Ogre::SBT_REPLACE );
00411 color_material_->setDepthWriteEnabled( true );
00412 }
00413 }
00414
00415 void RobotLink::updateVisibility()
00416 {
00417 bool enabled = getEnabled();
00418
00419 robot_->calculateJointCheckboxes();
00420
00421 if( visual_node_ )
00422 {
00423 visual_node_->setVisible( enabled && robot_->isVisible() && robot_->isVisualVisible() );
00424 }
00425 if( collision_node_ )
00426 {
00427 collision_node_->setVisible( enabled && robot_->isVisible() && robot_->isCollisionVisible() );
00428 }
00429 if( trail_ )
00430 {
00431 trail_->setVisible( enabled && robot_->isVisible() );
00432 }
00433 if( axes_ )
00434 {
00435 axes_->getSceneNode()->setVisible( enabled && robot_->isVisible() );
00436 }
00437 }
00438
00439 Ogre::MaterialPtr RobotLink::getMaterialForLink( const urdf::LinkConstPtr& link)
00440 {
00441 if (!link->visual || !link->visual->material)
00442 {
00443 return Ogre::MaterialManager::getSingleton().getByName("RVIZ/ShadedRed");
00444 }
00445
00446 static int count = 0;
00447 std::stringstream ss;
00448 ss << "Robot Link Material" << count;
00449
00450 Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME);
00451 mat->getTechnique(0)->setLightingEnabled(true);
00452 if (link->visual->material->texture_filename.empty())
00453 {
00454 const urdf::Color& col = link->visual->material->color;
00455 mat->getTechnique(0)->setAmbient(col.r * 0.5, col.g * 0.5, col.b * 0.5);
00456 mat->getTechnique(0)->setDiffuse(col.r, col.g, col.b, col.a);
00457
00458 material_alpha_ = col.a;
00459 }
00460 else
00461 {
00462 std::string filename = link->visual->material->texture_filename;
00463 if (!Ogre::TextureManager::getSingleton().resourceExists(filename))
00464 {
00465 resource_retriever::Retriever retriever;
00466 resource_retriever::MemoryResource res;
00467 try
00468 {
00469 res = retriever.get(filename);
00470 }
00471 catch (resource_retriever::Exception& e)
00472 {
00473 ROS_ERROR("%s", e.what());
00474 }
00475
00476 if (res.size != 0)
00477 {
00478 Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00479 Ogre::Image image;
00480 std::string extension = fs::extension(fs::path(filename));
00481
00482 if (extension[0] == '.')
00483 {
00484 extension = extension.substr(1, extension.size() - 1);
00485 }
00486
00487 try
00488 {
00489 image.load(stream, extension);
00490 Ogre::TextureManager::getSingleton().loadImage(filename, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
00491 }
00492 catch (Ogre::Exception& e)
00493 {
00494 ROS_ERROR("Could not load texture [%s]: %s", filename.c_str(), e.what());
00495 }
00496 }
00497 }
00498
00499 Ogre::Pass* pass = mat->getTechnique(0)->getPass(0);
00500 Ogre::TextureUnitState* tex_unit = pass->createTextureUnitState();;
00501 tex_unit->setTextureName(filename);
00502 }
00503
00504 return mat;
00505 }
00506
00507 void RobotLink::createEntityForGeometryElement(const urdf::LinkConstPtr& link, const urdf::Geometry& geom, const urdf::Pose& origin, Ogre::SceneNode* scene_node, Ogre::Entity*& entity)
00508 {
00509 entity = NULL;
00510 Ogre::SceneNode* offset_node = scene_node->createChildSceneNode();
00511
00512 static int count = 0;
00513 std::stringstream ss;
00514 ss << "Robot Link" << count++;
00515 std::string entity_name = ss.str();
00516
00517 Ogre::Vector3 scale(Ogre::Vector3::UNIT_SCALE);
00518
00519 Ogre::Vector3 offset_position(Ogre::Vector3::ZERO);
00520 Ogre::Quaternion offset_orientation(Ogre::Quaternion::IDENTITY);
00521
00522
00523 {
00524 Ogre::Vector3 position( origin.position.x, origin.position.y, origin.position.z );
00525 Ogre::Quaternion orientation( Ogre::Quaternion::IDENTITY );
00526 orientation = orientation * Ogre::Quaternion( origin.rotation.w, origin.rotation.x, origin.rotation.y, origin.rotation.z );
00527
00528 offset_position = position;
00529 offset_orientation = orientation;
00530 }
00531
00532 switch (geom.type)
00533 {
00534 case urdf::Geometry::SPHERE:
00535 {
00536 const urdf::Sphere& sphere = static_cast<const urdf::Sphere&>(geom);
00537 entity = Shape::createEntity(entity_name, Shape::Sphere, scene_manager_);
00538
00539 scale = Ogre::Vector3( sphere.radius*2, sphere.radius*2, sphere.radius*2 );
00540 break;
00541 }
00542 case urdf::Geometry::BOX:
00543 {
00544 const urdf::Box& box = static_cast<const urdf::Box&>(geom);
00545 entity = Shape::createEntity(entity_name, Shape::Cube, scene_manager_);
00546
00547 scale = Ogre::Vector3( box.dim.x, box.dim.y, box.dim.z );
00548
00549 break;
00550 }
00551 case urdf::Geometry::CYLINDER:
00552 {
00553 const urdf::Cylinder& cylinder = static_cast<const urdf::Cylinder&>(geom);
00554
00555 Ogre::Quaternion rotX;
00556 rotX.FromAngleAxis( Ogre::Degree(90), Ogre::Vector3::UNIT_X );
00557 offset_orientation = offset_orientation * rotX;
00558
00559 entity = Shape::createEntity(entity_name, Shape::Cylinder, scene_manager_);
00560 scale = Ogre::Vector3( cylinder.radius*2, cylinder.length, cylinder.radius*2 );
00561 break;
00562 }
00563 case urdf::Geometry::MESH:
00564 {
00565 const urdf::Mesh& mesh = static_cast<const urdf::Mesh&>(geom);
00566
00567 if ( mesh.filename.empty() )
00568 return;
00569
00570
00571
00572
00573 scale = Ogre::Vector3(mesh.scale.x, mesh.scale.y, mesh.scale.z);
00574
00575 std::string model_name = mesh.filename;
00576 loadMeshFromResource(model_name);
00577
00578 try
00579 {
00580 entity = scene_manager_->createEntity( ss.str(), model_name );
00581 }
00582 catch( Ogre::Exception& e )
00583 {
00584 ROS_ERROR( "Could not load model '%s' for link '%s': %s\n", model_name.c_str(), link->name.c_str(), e.what() );
00585 }
00586 break;
00587 }
00588 default:
00589 ROS_WARN("Unsupported geometry type for element: %d", geom.type);
00590 break;
00591 }
00592
00593 if ( entity )
00594 {
00595 offset_node->attachObject(entity);
00596 offset_node->setScale(scale);
00597 offset_node->setPosition(offset_position);
00598 offset_node->setOrientation(offset_orientation);
00599
00600 if (default_material_name_.empty())
00601 {
00602 default_material_ = getMaterialForLink(link);
00603
00604 static int count = 0;
00605 std::stringstream ss;
00606 ss << default_material_->getName() << count++ << "Robot";
00607 std::string cloned_name = ss.str();
00608
00609 default_material_ = default_material_->clone(cloned_name);
00610 default_material_name_ = default_material_->getName();
00611 }
00612
00613 for (uint32_t i = 0; i < entity->getNumSubEntities(); ++i)
00614 {
00615
00616 Ogre::SubEntity* sub = entity->getSubEntity(i);
00617 const std::string& material_name = sub->getMaterialName();
00618
00619 if (material_name == "BaseWhite" || material_name == "BaseWhiteNoLighting")
00620 {
00621 sub->setMaterialName(default_material_name_);
00622 }
00623 else
00624 {
00625
00626
00627 static int count = 0;
00628 std::stringstream ss;
00629 ss << material_name << count++ << "Robot";
00630 std::string cloned_name = ss.str();
00631 sub->getMaterial()->clone(cloned_name);
00632 sub->setMaterialName(cloned_name);
00633 }
00634
00635 materials_[sub] = sub->getMaterial();
00636 }
00637 }
00638 }
00639
00640 void RobotLink::createCollision(const urdf::LinkConstPtr& link)
00641 {
00642 bool valid_collision_found = false;
00643 std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<urdf::Collision> > > >::const_iterator mi;
00644 for( mi = link->collision_groups.begin(); mi != link->collision_groups.end(); mi++ )
00645 {
00646 if( mi->second )
00647 {
00648 std::vector<boost::shared_ptr<urdf::Collision> >::const_iterator vi;
00649 for( vi = mi->second->begin(); vi != mi->second->end(); vi++ )
00650 {
00651 boost::shared_ptr<urdf::Collision> collision = *vi;
00652 if( collision && collision->geometry )
00653 {
00654 Ogre::Entity* collision_mesh = NULL;
00655 createEntityForGeometryElement( link, *collision->geometry, collision->origin, collision_node_, collision_mesh );
00656 if( collision_mesh )
00657 {
00658 collision_meshes_.push_back( collision_mesh );
00659 valid_collision_found = true;
00660 }
00661 }
00662 }
00663 }
00664 }
00665
00666 if( !valid_collision_found && link->collision && link->collision->geometry )
00667 {
00668 Ogre::Entity* collision_mesh = NULL;
00669 createEntityForGeometryElement( link, *link->collision->geometry, link->collision->origin, collision_node_, collision_mesh );
00670 if( collision_mesh )
00671 {
00672 collision_meshes_.push_back( collision_mesh );
00673 }
00674 }
00675
00676 collision_node_->setVisible( getEnabled() );
00677 }
00678
00679 void RobotLink::createVisual(const urdf::LinkConstPtr& link )
00680 {
00681 bool valid_visual_found = false;
00682 std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<urdf::Visual> > > >::const_iterator mi;
00683 for( mi = link->visual_groups.begin(); mi != link->visual_groups.end(); mi++ )
00684 {
00685 if( mi->second )
00686 {
00687 std::vector<boost::shared_ptr<urdf::Visual> >::const_iterator vi;
00688 for( vi = mi->second->begin(); vi != mi->second->end(); vi++ )
00689 {
00690 boost::shared_ptr<urdf::Visual> visual = *vi;
00691 if( visual && visual->geometry )
00692 {
00693 Ogre::Entity* visual_mesh = NULL;
00694 createEntityForGeometryElement( link, *visual->geometry, visual->origin, visual_node_, visual_mesh );
00695 if( visual_mesh )
00696 {
00697 visual_meshes_.push_back( visual_mesh );
00698 valid_visual_found = true;
00699 }
00700 }
00701 }
00702 }
00703 }
00704
00705 if( !valid_visual_found && link->visual && link->visual->geometry )
00706 {
00707 Ogre::Entity* visual_mesh = NULL;
00708 createEntityForGeometryElement( link, *link->visual->geometry, link->visual->origin, visual_node_, visual_mesh );
00709 if( visual_mesh )
00710 {
00711 visual_meshes_.push_back( visual_mesh );
00712 }
00713 }
00714
00715 visual_node_->setVisible( getEnabled() );
00716 }
00717
00718 void RobotLink::createSelection()
00719 {
00720 selection_handler_.reset( new RobotLinkSelectionHandler( this, context_ ));
00721 for( size_t i = 0; i < visual_meshes_.size(); i++ )
00722 {
00723 selection_handler_->addTrackedObject( visual_meshes_[ i ]);
00724 }
00725 for( size_t i = 0; i < collision_meshes_.size(); i++ )
00726 {
00727 selection_handler_->addTrackedObject( collision_meshes_[ i ]);
00728 }
00729 }
00730
00731 void RobotLink::updateTrail()
00732 {
00733 if( trail_property_->getValue().toBool() )
00734 {
00735 if( !trail_ )
00736 {
00737 if( visual_node_ )
00738 {
00739 static int count = 0;
00740 std::stringstream ss;
00741 ss << "Trail for link " << name_ << count++;
00742 trail_ = scene_manager_->createRibbonTrail( ss.str() );
00743 trail_->setMaxChainElements( 100 );
00744 trail_->setInitialWidth( 0, 0.01f );
00745 trail_->setInitialColour( 0, 0.0f, 0.5f, 0.5f );
00746 trail_->addNode( visual_node_ );
00747 trail_->setTrailLength( 2.0f );
00748 trail_->setVisible( getEnabled() );
00749 robot_->getOtherNode()->attachObject( trail_ );
00750 }
00751 else
00752 {
00753 ROS_WARN( "No visual node for link %s, cannot create a trail", name_.c_str() );
00754 }
00755 }
00756 }
00757 else
00758 {
00759 if( trail_ )
00760 {
00761 scene_manager_->destroyRibbonTrail( trail_ );
00762 trail_ = NULL;
00763 }
00764 }
00765 }
00766
00767 void RobotLink::updateAxes()
00768 {
00769 if( axes_property_->getValue().toBool() )
00770 {
00771 if( !axes_ )
00772 {
00773 static int count = 0;
00774 std::stringstream ss;
00775 ss << "Axes for link " << name_ << count++;
00776 axes_ = new Axes( scene_manager_, robot_->getOtherNode(), 0.1, 0.01 );
00777 axes_->getSceneNode()->setVisible( getEnabled() );
00778
00779 axes_->setPosition( position_property_->getVector() );
00780 axes_->setOrientation( orientation_property_->getQuaternion() );
00781 }
00782 }
00783 else
00784 {
00785 if( axes_ )
00786 {
00787 delete axes_;
00788 axes_ = NULL;
00789 }
00790 }
00791 }
00792
00793 void RobotLink::setTransforms( const Ogre::Vector3& visual_position, const Ogre::Quaternion& visual_orientation,
00794 const Ogre::Vector3& collision_position, const Ogre::Quaternion& collision_orientation )
00795 {
00796 if ( visual_node_ )
00797 {
00798 visual_node_->setPosition( visual_position );
00799 visual_node_->setOrientation( visual_orientation );
00800 }
00801
00802 if ( collision_node_ )
00803 {
00804 collision_node_->setPosition( collision_position );
00805 collision_node_->setOrientation( collision_orientation );
00806 }
00807
00808 position_property_->setVector( visual_position );
00809 orientation_property_->setQuaternion( visual_orientation );
00810
00811 if ( axes_ )
00812 {
00813 axes_->setPosition( visual_position );
00814 axes_->setOrientation( visual_orientation );
00815 }
00816 }
00817
00818 void RobotLink::setToErrorMaterial()
00819 {
00820 for( size_t i = 0; i < visual_meshes_.size(); i++ )
00821 {
00822 visual_meshes_[ i ]->setMaterialName("BaseWhiteNoLighting");
00823 }
00824 for( size_t i = 0; i < collision_meshes_.size(); i++ )
00825 {
00826 collision_meshes_[ i ]->setMaterialName("BaseWhiteNoLighting");
00827 }
00828 }
00829
00830 void RobotLink::setToNormalMaterial()
00831 {
00832 if( using_color_ )
00833 {
00834 for( size_t i = 0; i < visual_meshes_.size(); i++ )
00835 {
00836 visual_meshes_[ i ]->setMaterial( color_material_ );
00837 }
00838 for( size_t i = 0; i < collision_meshes_.size(); i++ )
00839 {
00840 collision_meshes_[ i ]->setMaterial( color_material_ );
00841 }
00842 }
00843 else
00844 {
00845 M_SubEntityToMaterial::iterator it = materials_.begin();
00846 M_SubEntityToMaterial::iterator end = materials_.end();
00847 for (; it != end; ++it)
00848 {
00849 it->first->setMaterial(it->second);
00850 }
00851 }
00852 }
00853
00854 void RobotLink::setColor( float red, float green, float blue )
00855 {
00856 Ogre::ColourValue color = color_material_->getTechnique(0)->getPass(0)->getDiffuse();
00857 color.r = red;
00858 color.g = green;
00859 color.b = blue;
00860 color_material_->getTechnique(0)->setAmbient( 0.5 * color );
00861 color_material_->getTechnique(0)->setDiffuse( color );
00862
00863 using_color_ = true;
00864 setToNormalMaterial();
00865 }
00866
00867 void RobotLink::unsetColor()
00868 {
00869 using_color_ = false;
00870 setToNormalMaterial();
00871 }
00872
00873 bool RobotLink::setSelectable( bool selectable )
00874 {
00875 bool old = is_selectable_;
00876 is_selectable_ = selectable;
00877 return old;
00878 }
00879
00880 bool RobotLink::getSelectable()
00881 {
00882 return is_selectable_;
00883 }
00884
00885 void RobotLink::hideSubProperties(bool hide)
00886 {
00887 position_property_->setHidden(hide);
00888 orientation_property_->setHidden(hide);
00889 trail_property_->setHidden(hide);
00890 axes_property_->setHidden(hide);
00891 alpha_property_->setHidden(hide);
00892 }
00893
00894 Ogre::Vector3 RobotLink::getPosition()
00895 {
00896 return position_property_->getVector();
00897 }
00898
00899 Ogre::Quaternion RobotLink::getOrientation()
00900 {
00901 return orientation_property_->getQuaternion();
00902 }
00903
00904 void RobotLink::setParentProperty(Property* new_parent)
00905 {
00906 Property* old_parent = link_property_->getParent();
00907 if (old_parent)
00908 old_parent->takeChild(link_property_);
00909
00910 if (new_parent)
00911 new_parent->addChild(link_property_);
00912 }
00913
00914
00915
00916
00917
00918
00919
00920 void RobotLink::useDetailProperty(bool use_detail)
00921 {
00922 Property* old_parent = details_->getParent();
00923 if (old_parent)
00924 old_parent->takeChild(details_);
00925
00926 if (use_detail)
00927 {
00928 while (link_property_->numChildren() > 0)
00929 {
00930 Property* child = link_property_->childAt(0);
00931 link_property_->takeChild(child);
00932 details_->addChild(child);
00933 }
00934
00935 link_property_->addChild(details_);
00936 }
00937 else
00938 {
00939 while (details_->numChildren() > 0)
00940 {
00941 Property* child = details_->childAt(0);
00942 details_->takeChild(child);
00943 link_property_->addChild(child);
00944 }
00945 }
00946 }
00947
00948 void RobotLink::expandDetails(bool expand)
00949 {
00950 Property *parent = details_->getParent() ? details_ : link_property_;
00951 if (expand)
00952 {
00953 parent->expand();
00954 }
00955 else
00956 {
00957 parent->collapse();
00958 }
00959 }
00960
00961
00962 }
00963