$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Wim Meeussen */ 00036 00037 00038 #include <urdf_interface/link.h> 00039 #include <ros/console.h> 00040 #include <ros/package.h> 00041 #include <fstream> 00042 #include <boost/lexical_cast.hpp> 00043 #include <algorithm> 00044 00045 namespace urdf{ 00046 00047 boost::shared_ptr<Geometry> parseGeometry(TiXmlElement *g) 00048 { 00049 boost::shared_ptr<Geometry> geom; 00050 if (!g) return geom; 00051 00052 TiXmlElement *shape = g->FirstChildElement(); 00053 if (!shape) 00054 { 00055 ROS_ERROR("Geometry tag contains no child element."); 00056 return geom; 00057 } 00058 00059 std::string type_name = shape->ValueStr(); 00060 if (type_name == "sphere") 00061 geom.reset(new Sphere); 00062 else if (type_name == "box") 00063 geom.reset(new Box); 00064 else if (type_name == "cylinder") 00065 geom.reset(new Cylinder); 00066 else if (type_name == "mesh") 00067 geom.reset(new Mesh); 00068 else 00069 { 00070 ROS_ERROR("Unknown geometry type '%s'", type_name.c_str()); 00071 return geom; 00072 } 00073 00074 // clear geom object when fails to initialize 00075 if (!geom->initXml(shape)){ 00076 ROS_ERROR("Geometry failed to parse"); 00077 geom.reset(); 00078 } 00079 00080 return geom; 00081 } 00082 00083 bool Material::initXml(TiXmlElement *config) 00084 { 00085 bool has_rgb = false; 00086 bool has_filename = false; 00087 00088 this->clear(); 00089 00090 if (!config->Attribute("name")) 00091 { 00092 ROS_ERROR("Material must contain a name attribute"); 00093 return false; 00094 } 00095 00096 this->name = config->Attribute("name"); 00097 00098 // texture 00099 TiXmlElement *t = config->FirstChildElement("texture"); 00100 if (t) 00101 { 00102 if (t->Attribute("filename")) 00103 { 00104 this->texture_filename = t->Attribute("filename"); 00105 has_filename = true; 00106 } 00107 else 00108 { 00109 ROS_ERROR("texture has no filename for Material %s",this->name.c_str()); 00110 } 00111 } 00112 00113 // color 00114 TiXmlElement *c = config->FirstChildElement("color"); 00115 if (c) 00116 { 00117 if (c->Attribute("rgba")) 00118 { 00119 if (!this->color.init(c->Attribute("rgba"))) 00120 { 00121 ROS_ERROR("Material %s has malformed color rgba values.",this->name.c_str()); 00122 this->color.clear(); 00123 return false; 00124 } 00125 else 00126 has_rgb = true; 00127 } 00128 else 00129 { 00130 ROS_ERROR("Material %s color has no rgba",this->name.c_str()); 00131 } 00132 } 00133 00134 return (has_rgb || has_filename); 00135 } 00136 00137 bool Inertial::initXml(TiXmlElement *config) 00138 { 00139 this->clear(); 00140 00141 // Origin 00142 TiXmlElement *o = config->FirstChildElement("origin"); 00143 if (!o) 00144 { 00145 ROS_DEBUG("Origin tag not present for inertial element, using default (Identity)"); 00146 this->origin.clear(); 00147 } 00148 else 00149 { 00150 if (!this->origin.initXml(o)) 00151 { 00152 ROS_ERROR("Inertial has a malformed origin tag"); 00153 this->origin.clear(); 00154 return false; 00155 } 00156 } 00157 00158 TiXmlElement *mass_xml = config->FirstChildElement("mass"); 00159 if (!mass_xml) 00160 { 00161 ROS_ERROR("Inertial element must have mass element"); 00162 return false; 00163 } 00164 if (!mass_xml->Attribute("value")) 00165 { 00166 ROS_ERROR("Inertial: mass element must have value attributes"); 00167 return false; 00168 } 00169 00170 try 00171 { 00172 mass = boost::lexical_cast<double>(mass_xml->Attribute("value")); 00173 } 00174 catch (boost::bad_lexical_cast &e) 00175 { 00176 ROS_ERROR("mass (%s) is not a float",mass_xml->Attribute("value")); 00177 return false; 00178 } 00179 00180 TiXmlElement *inertia_xml = config->FirstChildElement("inertia"); 00181 if (!inertia_xml) 00182 { 00183 ROS_ERROR("Inertial element must have inertia element"); 00184 return false; 00185 } 00186 if (!(inertia_xml->Attribute("ixx") && inertia_xml->Attribute("ixy") && inertia_xml->Attribute("ixz") && 00187 inertia_xml->Attribute("iyy") && inertia_xml->Attribute("iyz") && 00188 inertia_xml->Attribute("izz"))) 00189 { 00190 ROS_ERROR("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz attributes"); 00191 return false; 00192 } 00193 try 00194 { 00195 ixx = boost::lexical_cast<double>(inertia_xml->Attribute("ixx")); 00196 ixy = boost::lexical_cast<double>(inertia_xml->Attribute("ixy")); 00197 ixz = boost::lexical_cast<double>(inertia_xml->Attribute("ixz")); 00198 iyy = boost::lexical_cast<double>(inertia_xml->Attribute("iyy")); 00199 iyz = boost::lexical_cast<double>(inertia_xml->Attribute("iyz")); 00200 izz = boost::lexical_cast<double>(inertia_xml->Attribute("izz")); 00201 } 00202 catch (boost::bad_lexical_cast &e) 00203 { 00204 ROS_ERROR("one of the inertia elements: ixx (%s) ixy (%s) ixz (%s) iyy (%s) iyz (%s) izz (%s) is not a valid double", 00205 inertia_xml->Attribute("ixx"), 00206 inertia_xml->Attribute("ixy"), 00207 inertia_xml->Attribute("ixz"), 00208 inertia_xml->Attribute("iyy"), 00209 inertia_xml->Attribute("iyz"), 00210 inertia_xml->Attribute("izz")); 00211 return false; 00212 } 00213 00214 return true; 00215 } 00216 00217 bool Visual::initXml(TiXmlElement *config) 00218 { 00219 this->clear(); 00220 00221 // Origin 00222 TiXmlElement *o = config->FirstChildElement("origin"); 00223 if (!o) 00224 { 00225 ROS_DEBUG("Origin tag not present for visual element, using default (Identity)"); 00226 this->origin.clear(); 00227 } 00228 else if (!this->origin.initXml(o)) 00229 { 00230 ROS_ERROR("Visual has a malformed origin tag"); 00231 this->origin.clear(); 00232 return false; 00233 } 00234 00235 // Geometry 00236 TiXmlElement *geom = config->FirstChildElement("geometry"); 00237 geometry = parseGeometry(geom); 00238 if (!geometry) 00239 { 00240 ROS_ERROR("Malformed geometry for Visual element"); 00241 return false; 00242 } 00243 00244 // Material 00245 TiXmlElement *mat = config->FirstChildElement("material"); 00246 if (!mat) 00247 { 00248 ROS_DEBUG("visual element has no material tag."); 00249 } 00250 else 00251 { 00252 // get material name 00253 if (!mat->Attribute("name")) 00254 { 00255 ROS_ERROR("Visual material must contain a name attribute"); 00256 return false; 00257 } 00258 this->material_name = mat->Attribute("name"); 00259 00260 // try to parse material element in place 00261 this->material.reset(new Material); 00262 if (!this->material->initXml(mat)) 00263 { 00264 ROS_DEBUG("Could not parse material element in Visual block, maybe defined outside."); 00265 this->material.reset(); 00266 } 00267 else 00268 { 00269 ROS_DEBUG("Parsed material element in Visual block."); 00270 } 00271 } 00272 00273 // Group Tag (optional) 00274 // collision blocks without a group tag are designated to the "default" group 00275 const char *group_name_char = config->Attribute("group"); 00276 if (!group_name_char) 00277 group_name = std::string("default"); 00278 else 00279 group_name = std::string(group_name_char); 00280 00281 return true; 00282 } 00283 00284 bool Collision::initXml(TiXmlElement* config) 00285 { 00286 this->clear(); 00287 00288 // Origin 00289 TiXmlElement *o = config->FirstChildElement("origin"); 00290 if (!o) 00291 { 00292 ROS_DEBUG("Origin tag not present for collision element, using default (Identity)"); 00293 this->origin.clear(); 00294 } 00295 else if (!this->origin.initXml(o)) 00296 { 00297 ROS_ERROR("Collision has a malformed origin tag"); 00298 this->origin.clear(); 00299 return false; 00300 } 00301 00302 // Geometry 00303 TiXmlElement *geom = config->FirstChildElement("geometry"); 00304 geometry = parseGeometry(geom); 00305 if (!geometry) 00306 { 00307 ROS_ERROR("Malformed geometry for Collision element"); 00308 return false; 00309 } 00310 00311 // Group Tag (optional) 00312 // collision blocks without a group tag are designated to the "default" group 00313 const char *group_name_char = config->Attribute("group"); 00314 if (!group_name_char) 00315 group_name = std::string("default"); 00316 else 00317 group_name = std::string(group_name_char); 00318 00319 return true; 00320 } 00321 00322 bool Sphere::initXml(TiXmlElement *c) 00323 { 00324 this->clear(); 00325 00326 this->type = SPHERE; 00327 if (!c->Attribute("radius")) 00328 { 00329 ROS_ERROR("Sphere shape must have a radius attribute"); 00330 return false; 00331 } 00332 00333 try 00334 { 00335 radius = boost::lexical_cast<double>(c->Attribute("radius")); 00336 } 00337 catch (boost::bad_lexical_cast &e) 00338 { 00339 ROS_ERROR("radius (%s) is not a valid float",c->Attribute("radius")); 00340 return false; 00341 } 00342 00343 return true; 00344 } 00345 00346 bool Box::initXml(TiXmlElement *c) 00347 { 00348 this->clear(); 00349 00350 this->type = BOX; 00351 if (!c->Attribute("size")) 00352 { 00353 ROS_ERROR("Box shape has no size attribute"); 00354 return false; 00355 } 00356 if (!dim.init(c->Attribute("size"))) 00357 { 00358 ROS_ERROR("Box shape has malformed size attribute"); 00359 dim.clear(); 00360 return false; 00361 } 00362 return true; 00363 } 00364 00365 bool Cylinder::initXml(TiXmlElement *c) 00366 { 00367 this->clear(); 00368 00369 this->type = CYLINDER; 00370 if (!c->Attribute("length") || 00371 !c->Attribute("radius")) 00372 { 00373 ROS_ERROR("Cylinder shape must have both length and radius attributes"); 00374 return false; 00375 } 00376 00377 try 00378 { 00379 length = boost::lexical_cast<double>(c->Attribute("length")); 00380 } 00381 catch (boost::bad_lexical_cast &e) 00382 { 00383 ROS_ERROR("length (%s) is not a valid float",c->Attribute("length")); 00384 return false; 00385 } 00386 00387 try 00388 { 00389 radius = boost::lexical_cast<double>(c->Attribute("radius")); 00390 } 00391 catch (boost::bad_lexical_cast &e) 00392 { 00393 ROS_ERROR("radius (%s) is not a valid float",c->Attribute("radius")); 00394 return false; 00395 } 00396 00397 return true; 00398 } 00399 00400 00401 bool Mesh::initXml(TiXmlElement *c) 00402 { 00403 this->clear(); 00404 00405 this->type = MESH; 00406 if (!c->Attribute("filename")) 00407 { 00408 ROS_ERROR("Mesh must contain a filename attribute"); 00409 return false; 00410 } 00411 00412 filename = c->Attribute("filename"); 00413 00414 if (c->Attribute("scale")) 00415 { 00416 if (!this->scale.init(c->Attribute("scale"))) 00417 { 00418 ROS_ERROR("Mesh scale was specified, but could not be parsed"); 00419 this->scale.clear(); 00420 return false; 00421 } 00422 } 00423 else 00424 ROS_DEBUG("Mesh scale was not specified, default to (1,1,1)"); 00425 00426 return true; 00427 } 00428 00429 00430 bool Link::initXml(TiXmlElement* config) 00431 { 00432 this->clear(); 00433 00434 const char *name_char = config->Attribute("name"); 00435 if (!name_char) 00436 { 00437 ROS_ERROR("No name given for the link."); 00438 return false; 00439 } 00440 name = std::string(name_char); 00441 00442 // Inertial (optional) 00443 TiXmlElement *i = config->FirstChildElement("inertial"); 00444 if (i) 00445 { 00446 inertial.reset(new Inertial); 00447 if (!inertial->initXml(i)) 00448 { 00449 ROS_ERROR("Could not parse inertial element for Link '%s'", this->name.c_str()); 00450 return false; 00451 } 00452 } 00453 00454 // Multiple Visuals (optional) 00455 for (TiXmlElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual")) 00456 { 00457 boost::shared_ptr<Visual> vis; 00458 vis.reset(new Visual); 00459 00460 if (vis->initXml(vis_xml)) 00461 { 00462 boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > viss = this->getVisuals(vis->group_name); 00463 if (!viss) 00464 { 00465 // group does not exist, create one and add to map 00466 viss.reset(new std::vector<boost::shared_ptr<Visual > >); 00467 // new group name, create vector, add vector to map and add Visual to the vector 00468 this->visual_groups.insert(make_pair(vis->group_name,viss)); 00469 ROS_DEBUG("successfully added a new visual group name '%s'",vis->group_name.c_str()); 00470 } 00471 00472 // group exists, add Visual to the vector in the map 00473 viss->push_back(vis); 00474 ROS_DEBUG("successfully added a new visual under group name '%s'",vis->group_name.c_str()); 00475 } 00476 else 00477 { 00478 ROS_ERROR("Could not parse visual element for Link '%s'", this->name.c_str()); 00479 vis.reset(); 00480 return false; 00481 } 00482 } 00483 // Visual (optional) 00484 // Assign one single default visual pointer from the visual_groups map 00485 this->visual.reset(); 00486 boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > default_visual = this->getVisuals("default"); 00487 if (!default_visual) 00488 { 00489 ROS_DEBUG("No 'default' visual group for Link '%s'", this->name.c_str()); 00490 } 00491 else if (default_visual->empty()) 00492 { 00493 ROS_DEBUG("'default' visual group is empty for Link '%s'", this->name.c_str()); 00494 } 00495 else 00496 { 00497 if (default_visual->size() > 1) 00498 ROS_WARN("'default' visual group has %d visuals for Link '%s', taking the first one as default",(int)default_visual->size(), this->name.c_str()); 00499 this->visual = (*default_visual->begin()); 00500 } 00501 00502 00503 00504 // Multiple Collisions (optional) 00505 for (TiXmlElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision")) 00506 { 00507 boost::shared_ptr<Collision> col; 00508 col.reset(new Collision); 00509 00510 if (col->initXml(col_xml)) 00511 { 00512 boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > cols = this->getCollisions(col->group_name); 00513 if (!cols) 00514 { 00515 // group does not exist, create one and add to map 00516 cols.reset(new std::vector<boost::shared_ptr<Collision > >); 00517 // new group name, create vector, add vector to map and add Collision to the vector 00518 this->collision_groups.insert(make_pair(col->group_name,cols)); 00519 ROS_DEBUG("successfully added a new collision group name '%s'",col->group_name.c_str()); 00520 } 00521 00522 // group exists, add Collision to the vector in the map 00523 cols->push_back(col); 00524 ROS_DEBUG("successfully added a new collision under group name '%s'",col->group_name.c_str()); 00525 } 00526 else 00527 { 00528 ROS_ERROR("Could not parse collision element for Link '%s'", this->name.c_str()); 00529 col.reset(); 00530 return false; 00531 } 00532 } 00533 00534 // Collision (optional) 00535 // Assign one single default collision pointer from the collision_groups map 00536 this->collision.reset(); 00537 boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > default_collision = this->getCollisions("default"); 00538 if (!default_collision) 00539 { 00540 ROS_DEBUG("No 'default' collision group for Link '%s'", this->name.c_str()); 00541 } 00542 else if (default_collision->empty()) 00543 { 00544 ROS_DEBUG("'default' collision group is empty for Link '%s'", this->name.c_str()); 00545 } 00546 else 00547 { 00548 if (default_collision->size() > 1) 00549 ROS_WARN("'default' collision group has %d collisions for Link '%s', taking the first one as default",(int)default_collision->size(), this->name.c_str()); 00550 this->collision = (*default_collision->begin()); 00551 } 00552 00553 return true; 00554 } 00555 00556 void Link::addVisual(std::string group_name, boost::shared_ptr<Visual> visual) 00557 { 00558 boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > viss = this->getVisuals(group_name); 00559 if (!viss) 00560 { 00561 // group does not exist, create one and add to map 00562 viss.reset(new std::vector<boost::shared_ptr<Visual > >); 00563 // new group name, create vector, add vector to map and add Visual to the vector 00564 this->visual_groups.insert(make_pair(group_name,viss)); 00565 ROS_DEBUG("successfully added a new visual group name '%s'",group_name.c_str()); 00566 } 00567 00568 // group exists, add Visual to the vector in the map 00569 std::vector<boost::shared_ptr<Visual > >::iterator vis_it = find(viss->begin(),viss->end(),visual); 00570 if (vis_it != viss->end()) 00571 ROS_WARN("attempted to add a visual that already exists under group name '%s', skipping.",group_name.c_str()); 00572 else 00573 viss->push_back(visual); 00574 ROS_DEBUG("successfully added a new visual under group name '%s'",group_name.c_str()); 00575 00576 } 00577 00578 boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > Link::getVisuals(const std::string& group_name) const 00579 { 00580 boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > ptr; 00581 if (this->visual_groups.find(group_name) == this->visual_groups.end()) 00582 ptr.reset(); 00583 else 00584 ptr = this->visual_groups.find(group_name)->second; 00585 return ptr; 00586 } 00587 00588 00589 void Link::addCollision(std::string group_name, boost::shared_ptr<Collision> collision) 00590 { 00591 boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > viss = this->getCollisions(group_name); 00592 if (!viss) 00593 { 00594 // group does not exist, create one and add to map 00595 viss.reset(new std::vector<boost::shared_ptr<Collision > >); 00596 // new group name, create vector, add vector to map and add Collision to the vector 00597 this->collision_groups.insert(make_pair(group_name,viss)); 00598 ROS_DEBUG("successfully added a new collision group name '%s'",group_name.c_str()); 00599 } 00600 00601 // group exists, add Collision to the vector in the map 00602 std::vector<boost::shared_ptr<Collision > >::iterator vis_it = find(viss->begin(),viss->end(),collision); 00603 if (vis_it != viss->end()) 00604 ROS_WARN("attempted to add a collision that already exists under group name '%s', skipping.",group_name.c_str()); 00605 else 00606 viss->push_back(collision); 00607 ROS_DEBUG("successfully added a new collision under group name '%s'",group_name.c_str()); 00608 00609 } 00610 00611 boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > Link::getCollisions(const std::string& group_name) const 00612 { 00613 boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > ptr; 00614 if (this->collision_groups.find(group_name) == this->collision_groups.end()) 00615 ptr.reset(); 00616 else 00617 ptr = this->collision_groups.find(group_name)->second; 00618 return ptr; 00619 } 00620 00621 void Link::setParent(boost::shared_ptr<Link> parent) 00622 { 00623 this->parent_link_ = parent; 00624 ROS_DEBUG("set parent Link '%s' for Link '%s'", parent->name.c_str(), this->name.c_str()); 00625 } 00626 00627 void Link::setParentJoint(boost::shared_ptr<Joint> parent) 00628 { 00629 this->parent_joint = parent; 00630 ROS_DEBUG("set parent joint '%s' to Link '%s'", parent->name.c_str(), this->name.c_str()); 00631 } 00632 00633 void Link::addChild(boost::shared_ptr<Link> child) 00634 { 00635 this->child_links.push_back(child); 00636 ROS_DEBUG("added child Link '%s' to Link '%s'", child->name.c_str(), this->name.c_str()); 00637 } 00638 00639 void Link::addChildJoint(boost::shared_ptr<Joint> child) 00640 { 00641 this->child_joints.push_back(child); 00642 ROS_DEBUG("added child Joint '%s' to Link '%s'", child->name.c_str(), this->name.c_str()); 00643 } 00644 00645 00646 00647 } 00648