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 "robot_link.h"
00031 #include "robot.h"
00032 #include "common.h"
00033 #include "properties/property.h"
00034 #include "properties/property_manager.h"
00035 #include "visualization_manager.h"
00036 #include "selection/selection_manager.h"
00037 #include "mesh_loader.h"
00038
00039 #include "ogre_tools/stl_loader.h"
00040 #include "ogre_tools/object.h"
00041 #include "ogre_tools/shape.h"
00042 #include "ogre_tools/axes.h"
00043
00044 #include <urdf/model.h>
00045 #include <urdf/link.h>
00046
00047 #include <OGRE/OgreSceneNode.h>
00048 #include <OGRE/OgreSceneManager.h>
00049 #include <OGRE/OgreRibbonTrail.h>
00050 #include <OGRE/OgreEntity.h>
00051 #include <OGRE/OgreSubEntity.h>
00052 #include <OGRE/OgreMaterialManager.h>
00053 #include <OGRE/OgreMaterial.h>
00054 #include <OGRE/OgreTextureManager.h>
00055
00056 #include <ros/console.h>
00057
00058 #include <resource_retriever/retriever.h>
00059
00060 #include <boost/filesystem.hpp>
00061
00062 namespace fs=boost::filesystem;
00063
00064 namespace rviz
00065 {
00066
00067 class RobotLinkSelectionHandler : public SelectionHandler
00068 {
00069 public:
00070 RobotLinkSelectionHandler(RobotLink* link);
00071 virtual ~RobotLinkSelectionHandler();
00072
00073 virtual void createProperties(const Picked& obj, PropertyManager* property_manager);
00074
00075 private:
00076 RobotLink* link_;
00077 };
00078
00079 RobotLinkSelectionHandler::RobotLinkSelectionHandler(RobotLink* link)
00080 : link_(link)
00081 {
00082 }
00083
00084 RobotLinkSelectionHandler::~RobotLinkSelectionHandler()
00085 {
00086 }
00087
00088 void RobotLinkSelectionHandler::createProperties(const Picked& obj, PropertyManager* property_manager)
00089 {
00090 std::stringstream ss;
00091 ss << link_->getName() << " Link " << link_->getName();
00092
00093 CategoryPropertyWPtr cat = property_manager->createCategory( "Link " + link_->getName(), ss.str(), CategoryPropertyWPtr(), (void*)obj.handle );
00094 properties_.push_back(cat);
00095
00096 properties_.push_back(property_manager->createProperty<Vector3Property>( "Position", ss.str(), boost::bind( &RobotLink::getPositionInRobotFrame, link_ ),
00097 Vector3Property::Setter(), cat, (void*)obj.handle ));
00098
00099 properties_.push_back(property_manager->createProperty<QuaternionProperty>( "Orientation", ss.str(), boost::bind( &RobotLink::getOrientationInRobotFrame, link_ ),
00100 QuaternionProperty::Setter(), cat, (void*)obj.handle ));
00101 }
00102
00103 RobotLink::RobotLink(Robot* parent, VisualizationManager* manager)
00104 : parent_(parent)
00105 , scene_manager_(manager->getSceneManager())
00106 , property_manager_(0)
00107 , vis_manager_(manager)
00108 , visual_mesh_( NULL )
00109 , collision_mesh_( NULL )
00110 , visual_node_( NULL )
00111 , collision_node_( NULL )
00112 , position_(Ogre::Vector3::ZERO)
00113 , orientation_(Ogre::Quaternion::IDENTITY)
00114 , trail_( NULL )
00115 , axes_( NULL )
00116 , selection_object_(NULL)
00117 {
00118 }
00119
00120 RobotLink::~RobotLink()
00121 {
00122 if ( visual_mesh_ )
00123 {
00124 scene_manager_->destroyEntity( visual_mesh_ );
00125 }
00126
00127 if ( collision_mesh_ )
00128 {
00129 scene_manager_->destroyEntity( collision_mesh_ );
00130 }
00131
00132 if ( trail_ )
00133 {
00134 scene_manager_->destroyRibbonTrail( trail_ );
00135 }
00136
00137 delete axes_;
00138
00139 if (selection_object_)
00140 {
00141 vis_manager_->getSelectionManager()->removeObject(selection_object_);
00142 }
00143
00144 if (property_manager_)
00145 {
00146 property_manager_->deleteByUserData(this);
00147 }
00148 }
00149
00150 bool RobotLink::isValid()
00151 {
00152 return visual_mesh_ || collision_mesh_;
00153 }
00154
00155 void RobotLink::load(TiXmlElement* root_element, urdf::Model& descr, const urdf::LinkConstPtr& link, bool visual, bool collision)
00156 {
00157 name_ = link->name;
00158
00159 if ( visual )
00160 {
00161 createVisual( root_element, link );
00162 }
00163
00164 if ( collision )
00165 {
00166 createCollision( root_element, link );
00167 }
00168
00169 if (collision || visual)
00170 {
00171 createSelection( descr, link );
00172 }
00173
00174 if ( property_manager_ )
00175 {
00176 createProperties();
00177 }
00178 }
00179
00180 void RobotLink::setAlpha(float a)
00181 {
00182 M_SubEntityToMaterial::iterator it = materials_.begin();
00183 M_SubEntityToMaterial::iterator end = materials_.end();
00184 for (; it != end; ++it)
00185 {
00186 const Ogre::MaterialPtr& material = it->second;
00187
00188 Ogre::ColourValue color = material->getTechnique(0)->getPass(0)->getDiffuse();
00189 color.a = a;
00190 material->setDiffuse( color );
00191
00192 if ( a < 0.9998 )
00193 {
00194 material->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00195 material->setDepthWriteEnabled( false );
00196 }
00197 else
00198 {
00199 material->setSceneBlending( Ogre::SBT_REPLACE );
00200 material->setDepthWriteEnabled( true );
00201 }
00202 }
00203 }
00204
00205 Ogre::MaterialPtr getMaterialForLink(TiXmlElement* root_element, const urdf::LinkConstPtr& link)
00206 {
00207 if (!link->visual || !link->visual->material)
00208 {
00209 return Ogre::MaterialManager::getSingleton().getByName("RVIZ/Red");
00210 }
00211
00212 static int count = 0;
00213 std::stringstream ss;
00214 ss << "Robot Link Material" << count;
00215
00216 Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME);
00217 mat->getTechnique(0)->setLightingEnabled(true);
00218 if (link->visual->material->texture_filename.empty())
00219 {
00220 const urdf::Color& col = link->visual->material->color;
00221 mat->getTechnique(0)->setAmbient(col.r * 0.5, col.g * 0.5, col.b * 0.5);
00222 mat->getTechnique(0)->setDiffuse(col.r, col.g, col.b, col.a);
00223 }
00224 else
00225 {
00226 std::string filename = link->visual->material->texture_filename;
00227 if (!Ogre::TextureManager::getSingleton().resourceExists(filename))
00228 {
00229 resource_retriever::Retriever retriever;
00230 resource_retriever::MemoryResource res;
00231 try
00232 {
00233 res = retriever.get(filename);
00234 }
00235 catch (resource_retriever::Exception& e)
00236 {
00237 ROS_ERROR("%s", e.what());
00238 }
00239
00240 if (res.size != 0)
00241 {
00242 Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00243 Ogre::Image image;
00244 std::string extension = fs::extension(fs::path(filename));
00245
00246 if (extension[0] == '.')
00247 {
00248 extension = extension.substr(1, extension.size() - 1);
00249 }
00250
00251 try
00252 {
00253 image.load(stream, extension);
00254 Ogre::TextureManager::getSingleton().loadImage(filename, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
00255 }
00256 catch (Ogre::Exception& e)
00257 {
00258 ROS_ERROR("Could not load texture [%s]: %s", filename.c_str(), e.what());
00259 }
00260 }
00261 }
00262
00263 Ogre::Pass* pass = mat->getTechnique(0)->getPass(0);
00264 Ogre::TextureUnitState* tex_unit = pass->createTextureUnitState();;
00265 tex_unit->setTextureName(filename);
00266 }
00267
00268 return mat;
00269 }
00270
00271 void RobotLink::createEntityForGeometryElement(TiXmlElement* root_element, const urdf::LinkConstPtr& link, const urdf::Geometry& geom, const urdf::Pose& origin, Ogre::SceneNode* parent_node, Ogre::Entity*& entity, Ogre::SceneNode*& scene_node, Ogre::SceneNode*& offset_node)
00272 {
00273 scene_node = parent_node->createChildSceneNode();
00274 offset_node = scene_node->createChildSceneNode();
00275
00276 static int count = 0;
00277 std::stringstream ss;
00278 ss << "Robot Link" << count++;
00279 std::string entity_name = ss.str();
00280
00281 Ogre::Vector3 scale(Ogre::Vector3::UNIT_SCALE);
00282
00283 Ogre::Vector3 offset_position(Ogre::Vector3::ZERO);
00284 Ogre::Quaternion offset_orientation(Ogre::Quaternion::IDENTITY);
00285
00286
00287 {
00288 Ogre::Vector3 position( origin.position.x, origin.position.y, origin.position.z );
00289 Ogre::Quaternion orientation( Ogre::Quaternion::IDENTITY );
00290 ogreToRobot( orientation );
00291 orientation = orientation * Ogre::Quaternion( origin.rotation.w, origin.rotation.x, origin.rotation.y, origin.rotation.z );
00292 robotToOgre( orientation );
00293
00294 offset_position = position;
00295 offset_orientation = orientation;
00296 }
00297
00298 switch (geom.type)
00299 {
00300 case urdf::Geometry::SPHERE:
00301 {
00302 const urdf::Sphere& sphere = static_cast<const urdf::Sphere&>(geom);
00303 entity = ogre_tools::Shape::createEntity(entity_name, ogre_tools::Shape::Sphere, scene_manager_);
00304
00305 scale = Ogre::Vector3( sphere.radius*2, sphere.radius*2, sphere.radius*2 );
00306 break;
00307 }
00308 case urdf::Geometry::BOX:
00309 {
00310 const urdf::Box& box = static_cast<const urdf::Box&>(geom);
00311 entity = ogre_tools::Shape::createEntity(entity_name, ogre_tools::Shape::Cube, scene_manager_);
00312
00313 scale = Ogre::Vector3( box.dim.x, box.dim.y, box.dim.z );
00314
00315
00316 break;
00317 }
00318 case urdf::Geometry::CYLINDER:
00319 {
00320 const urdf::Cylinder& cylinder = static_cast<const urdf::Cylinder&>(geom);
00321
00322 Ogre::Quaternion rotX;
00323 rotX.FromAngleAxis( Ogre::Degree(90), Ogre::Vector3::UNIT_X );
00324 offset_orientation = offset_orientation * rotX;
00325
00326 entity = ogre_tools::Shape::createEntity(entity_name, ogre_tools::Shape::Cylinder, scene_manager_);
00327 scale = Ogre::Vector3( cylinder.radius*2, cylinder.length, cylinder.radius*2 );
00328 break;
00329 }
00330 case urdf::Geometry::MESH:
00331 {
00332 const urdf::Mesh& mesh = static_cast<const urdf::Mesh&>(geom);
00333
00334 if ( mesh.filename.empty() )
00335 return;
00336
00337 scale = Ogre::Vector3(mesh.scale.x, mesh.scale.y, mesh.scale.z);
00338
00339 std::string model_name = mesh.filename;
00340 loadMeshFromResource(model_name);
00341
00342 try
00343 {
00344 entity = scene_manager_->createEntity( ss.str(), model_name );
00345 }
00346 catch( Ogre::Exception& e )
00347 {
00348 ROS_ERROR( "Could not load model '%s' for link '%s': %s\n", model_name.c_str(), link->name.c_str(), e.what() );
00349 }
00350 break;
00351 }
00352 default:
00353 ROS_WARN("Unsupported geometry type for element: %d", geom.type);
00354 break;
00355 }
00356
00357 if ( entity )
00358 {
00359 offset_node->attachObject(entity);
00360 offset_node->setScale(scale);
00361 offset_node->setPosition(offset_position);
00362 offset_node->setOrientation(offset_orientation);
00363
00364 if (default_material_name_.empty())
00365 {
00366 default_material_ = getMaterialForLink(root_element, link);
00367
00368 static int count = 0;
00369 std::stringstream ss;
00370 ss << default_material_->getName() << count++ << "Robot";
00371 std::string cloned_name = ss.str();
00372
00373 default_material_ = default_material_->clone(cloned_name);
00374 default_material_name_ = default_material_->getName();
00375 }
00376
00377 for (uint32_t i = 0; i < entity->getNumSubEntities(); ++i)
00378 {
00379
00380 Ogre::SubEntity* sub = entity->getSubEntity(i);
00381 const std::string& material_name = sub->getMaterialName();
00382
00383 if (material_name == "BaseWhite" || material_name == "BaseWhiteNoLighting")
00384 {
00385 sub->setMaterialName(default_material_name_);
00386 }
00387 else
00388 {
00389
00390
00391 static int count = 0;
00392 std::stringstream ss;
00393 ss << material_name << count++ << "Robot";
00394 std::string cloned_name = ss.str();
00395 sub->getMaterial()->clone(cloned_name);
00396 sub->setMaterialName(cloned_name);
00397 }
00398
00399 materials_[sub] = sub->getMaterial();
00400 }
00401 }
00402 }
00403
00404 void RobotLink::createCollision(TiXmlElement* root_element, const urdf::LinkConstPtr& link)
00405 {
00406 if (!link->collision || !link->collision->geometry)
00407 return;
00408
00409 createEntityForGeometryElement(root_element, link, *link->collision->geometry, link->collision->origin, parent_->getCollisionNode(), collision_mesh_, collision_node_, collision_offset_node_);
00410 }
00411
00412 void RobotLink::createVisual(TiXmlElement* root_element, const urdf::LinkConstPtr& link )
00413 {
00414 if (!link->visual || !link->visual->geometry)
00415 return;
00416
00417 createEntityForGeometryElement(root_element, link, *link->visual->geometry, link->visual->origin, parent_->getVisualNode(), visual_mesh_, visual_node_, visual_offset_node_);
00418 }
00419
00420 void RobotLink::createSelection(const urdf::Model& descr, const urdf::LinkConstPtr& link)
00421 {
00422 selection_handler_ = RobotLinkSelectionHandlerPtr(new RobotLinkSelectionHandler(this));
00423 SelectionManager* sel_man = vis_manager_->getSelectionManager();
00424 selection_object_ = sel_man->createHandle();
00425 sel_man->addObject(selection_object_, selection_handler_);
00426
00427 M_SubEntityToMaterial::iterator it = materials_.begin();
00428 M_SubEntityToMaterial::iterator end = materials_.end();
00429 for (; it != end; ++it)
00430 {
00431 const Ogre::MaterialPtr& material = it->second;
00432
00433 sel_man->addPickTechnique(selection_object_, material);
00434 }
00435
00436 if (visual_mesh_)
00437 {
00438 selection_handler_->addTrackedObject(visual_mesh_);
00439 }
00440
00441 if (collision_mesh_)
00442 {
00443 selection_handler_->addTrackedObject(collision_mesh_);
00444 }
00445 }
00446
00447 void RobotLink::setPropertyManager(PropertyManager* property_manager)
00448 {
00449 property_manager_ = property_manager;
00450 }
00451
00452 void RobotLink::createProperties()
00453 {
00454 ROS_ASSERT( property_manager_ );
00455
00456 std::stringstream ss;
00457 ss << parent_->getName() << " Link " << name_;
00458
00459 CategoryPropertyWPtr cat = property_manager_->createCategory( name_, ss.str(), parent_->getLinksCategory(), this );
00460
00461
00462 trail_property_ = property_manager_->createProperty<BoolProperty>( "Show Trail", ss.str(), boost::bind( &RobotLink::getShowTrail, this ),
00463 boost::bind( &RobotLink::setShowTrail, this, _1 ), cat, this );
00464 setPropertyHelpText(trail_property_, "Enable/disable a 2 meter \"ribbon\" which follows this link.");
00465
00466 axes_property_ = property_manager_->createProperty<BoolProperty>( "Show Axes", ss.str(), boost::bind( &RobotLink::getShowAxes, this ),
00467 boost::bind( &RobotLink::setShowAxes, this, _1 ), cat, this );
00468 setPropertyHelpText(axes_property_, "Enable/disable showing the axes of this link.");
00469
00470 position_property_ = property_manager_->createProperty<Vector3Property>( "Position", ss.str(), boost::bind( &RobotLink::getPositionInRobotFrame, this ),
00471 Vector3Property::Setter(), cat, this );
00472 setPropertyHelpText(position_property_, "Position of this link, in the current Fixed Frame. (Not editable)");
00473 orientation_property_ = property_manager_->createProperty<QuaternionProperty>( "Orientation", ss.str(), boost::bind( &RobotLink::getOrientationInRobotFrame, this ),
00474 QuaternionProperty::Setter(), cat, this );
00475 setPropertyHelpText(orientation_property_, "Orientation of this link, in the current Fixed Frame. (Not editable)");
00476
00477 CategoryPropertyPtr cat_prop = cat.lock();
00478 cat_prop->collapse();
00479 }
00480
00481
00482 Ogre::Vector3 RobotLink::getPositionInRobotFrame()
00483 {
00484 Ogre::Vector3 pos( position_ );
00485 ogreToRobot( pos );
00486
00487 return pos;
00488 }
00489
00490 Ogre::Quaternion RobotLink::getOrientationInRobotFrame()
00491 {
00492 Ogre::Quaternion orient( orientation_ );
00493 ogreToRobot( orient );
00494
00495 return orient;
00496 }
00497
00498 void RobotLink::setShowTrail(bool show)
00499 {
00500 if ( show )
00501 {
00502 if ( !trail_ )
00503 {
00504 if ( visual_node_ )
00505 {
00506 static int count = 0;
00507 std::stringstream ss;
00508 ss << "Trail for link " << name_ << count++;
00509 trail_ = scene_manager_->createRibbonTrail( ss.str() );
00510 trail_->setMaxChainElements( 100 );
00511 trail_->setInitialWidth( 0, 0.01f );
00512 trail_->setInitialColour( 0, 0.0f, 0.5f, 0.5f );
00513 trail_->addNode( visual_node_ );
00514 trail_->setTrailLength( 2.0f );
00515 parent_->getOtherNode()->attachObject( trail_ );
00516 }
00517 else
00518 {
00519 ROS_WARN( "No visual node for link %s, cannot create a trail", name_.c_str() );
00520 }
00521 }
00522 }
00523 else
00524 {
00525 if ( trail_ )
00526 {
00527 scene_manager_->destroyRibbonTrail( trail_ );
00528 trail_ = NULL;
00529 }
00530 }
00531
00532 propertyChanged(trail_property_);
00533 }
00534
00535 bool RobotLink::getShowTrail()
00536 {
00537 return trail_ != NULL;
00538 }
00539
00540 void RobotLink::setShowAxes(bool show)
00541 {
00542 if ( show )
00543 {
00544 if ( !axes_ )
00545 {
00546 static int count = 0;
00547 std::stringstream ss;
00548 ss << "Axes for link " << name_ << count++;
00549 axes_ = new ogre_tools::Axes( scene_manager_, parent_->getOtherNode(), 0.1, 0.01 );
00550 }
00551 }
00552 else
00553 {
00554 if ( axes_ )
00555 {
00556 delete axes_;
00557 axes_ = NULL;
00558 }
00559 }
00560
00561 propertyChanged(axes_property_);
00562 }
00563
00564 bool RobotLink::getShowAxes()
00565 {
00566 return axes_ != NULL;
00567 }
00568
00569 void RobotLink::setTransforms( const Ogre::Vector3& visual_position, const Ogre::Quaternion& visual_orientation,
00570 const Ogre::Vector3& collision_position, const Ogre::Quaternion& collision_orientation, bool apply_offset_transforms )
00571 {
00572 position_ = visual_position;
00573 orientation_ = visual_orientation;
00574
00575 if ( visual_node_ )
00576 {
00577 visual_node_->setPosition( visual_position );
00578 visual_node_->setOrientation( visual_orientation );
00579 }
00580
00581 if ( collision_node_ )
00582 {
00583 collision_node_->setPosition( collision_position );
00584 collision_node_->setOrientation( collision_orientation );
00585 }
00586
00587 if (property_manager_)
00588 {
00589 propertyChanged(position_property_);
00590 propertyChanged(orientation_property_);
00591 }
00592
00593
00594 if ( axes_ )
00595 {
00596 axes_->setPosition( position_ );
00597 axes_->setOrientation( orientation_ );
00598 }
00599 }
00600
00601 void RobotLink::setToErrorMaterial()
00602 {
00603 if (visual_mesh_)
00604 {
00605 visual_mesh_->setMaterialName("BaseWhiteNoLighting");
00606 }
00607
00608 if (collision_mesh_)
00609 {
00610 collision_mesh_->setMaterialName("BaseWhiteNoLighting");
00611 }
00612 }
00613
00614 void RobotLink::setToNormalMaterial()
00615 {
00616 M_SubEntityToMaterial::iterator it = materials_.begin();
00617 M_SubEntityToMaterial::iterator end = materials_.end();
00618 for (; it != end; ++it)
00619 {
00620 it->first->setMaterial(it->second);
00621 }
00622 }
00623
00624 }
00625