joint.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software Ligcense 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: John Hsu */
00036 
00037 #include <urdf_interface/joint.h>
00038 #include <ros/console.h>
00039 #include <boost/lexical_cast.hpp>
00040 
00041 namespace urdf{
00042 
00043 bool JointDynamics::initXml(TiXmlElement* config)
00044 {
00045   this->clear();
00046 
00047   // Get joint damping
00048   const char* damping_str = config->Attribute("damping");
00049   if (damping_str == NULL){
00050     ROS_DEBUG("joint dynamics: no damping, defaults to 0");
00051     this->damping = 0;
00052   }
00053   else
00054   {
00055     try
00056     {
00057       this->damping = boost::lexical_cast<double>(damping_str);
00058     }
00059     catch (boost::bad_lexical_cast &e)
00060     {
00061       ROS_ERROR("damping value (%s) is not a float",damping_str);
00062       return false;
00063     }
00064   }
00065 
00066   // Get joint friction
00067   const char* friction_str = config->Attribute("friction");
00068   if (friction_str == NULL){
00069     ROS_DEBUG("joint dynamics: no friction, defaults to 0");
00070     this->friction = 0;
00071   }
00072   else
00073   {
00074     try
00075     {
00076       this->friction = boost::lexical_cast<double>(friction_str);
00077     }
00078     catch (boost::bad_lexical_cast &e)
00079     {
00080       ROS_ERROR("friction value (%s) is not a float",friction_str);
00081       return false;
00082     }
00083   }
00084 
00085   if (damping_str == NULL && friction_str == NULL)
00086   {
00087     ROS_ERROR("joint dynamics element specified with no damping and no friction");
00088     return false;
00089   }
00090   else{
00091     ROS_DEBUG("joint dynamics: damping %f and friction %f", damping, friction);
00092     return true;
00093   }
00094 }
00095 
00096 bool JointLimits::initXml(TiXmlElement* config)
00097 {
00098   this->clear();
00099 
00100   // Get lower joint limit
00101   const char* lower_str = config->Attribute("lower");
00102   if (lower_str == NULL){
00103     ROS_DEBUG("joint limit: no lower, defaults to 0");
00104     this->lower = 0;
00105   }
00106   else
00107   {
00108     try
00109     {
00110       this->lower = boost::lexical_cast<double>(lower_str);
00111     }
00112     catch (boost::bad_lexical_cast &e)
00113     {
00114       ROS_ERROR("lower value (%s) is not a float",lower_str);
00115       return false;
00116     }
00117   }
00118 
00119   // Get upper joint limit
00120   const char* upper_str = config->Attribute("upper");
00121   if (upper_str == NULL){
00122     ROS_DEBUG("joint limit: no upper, , defaults to 0");
00123     this->upper = 0;
00124   }
00125   else
00126   {
00127     try
00128     {
00129       this->upper = boost::lexical_cast<double>(upper_str);
00130     }
00131     catch (boost::bad_lexical_cast &e)
00132     {
00133       ROS_ERROR("upper value (%s) is not a float",upper_str);
00134       return false;
00135     }
00136   }
00137 
00138   // Get joint effort limit
00139   const char* effort_str = config->Attribute("effort");
00140   if (effort_str == NULL){
00141     ROS_ERROR("joint limit: no effort");
00142     return false;
00143   }
00144   else
00145   {
00146     try
00147     {
00148       this->effort = boost::lexical_cast<double>(effort_str);
00149     }
00150     catch (boost::bad_lexical_cast &e)
00151     {
00152       ROS_ERROR("effort value (%s) is not a float",effort_str);
00153       return false;
00154     }
00155   }
00156 
00157   // Get joint velocity limit
00158   const char* velocity_str = config->Attribute("velocity");
00159   if (velocity_str == NULL){
00160     ROS_ERROR("joint limit: no velocity");
00161     return false;
00162   }
00163   else
00164   {
00165     try
00166     {
00167       this->velocity = boost::lexical_cast<double>(velocity_str);
00168     }
00169     catch (boost::bad_lexical_cast &e)
00170     {
00171       ROS_ERROR("velocity value (%s) is not a float",velocity_str);
00172       return false;
00173     }
00174   }
00175 
00176   return true;
00177 }
00178 
00179 bool JointSafety::initXml(TiXmlElement* config)
00180 {
00181   this->clear();
00182 
00183   // Get soft_lower_limit joint limit
00184   const char* soft_lower_limit_str = config->Attribute("soft_lower_limit");
00185   if (soft_lower_limit_str == NULL)
00186   {
00187     ROS_DEBUG("joint safety: no soft_lower_limit, using default value");
00188     this->soft_lower_limit = 0;
00189   }
00190   else
00191   {
00192     try
00193     {
00194       this->soft_lower_limit = boost::lexical_cast<double>(soft_lower_limit_str);
00195     }
00196     catch (boost::bad_lexical_cast &e)
00197     {
00198       ROS_ERROR("soft_lower_limit value (%s) is not a float",soft_lower_limit_str);
00199       return false;
00200     }
00201   }
00202 
00203   // Get soft_upper_limit joint limit
00204   const char* soft_upper_limit_str = config->Attribute("soft_upper_limit");
00205   if (soft_upper_limit_str == NULL)
00206   {
00207     ROS_DEBUG("joint safety: no soft_upper_limit, using default value");
00208     this->soft_upper_limit = 0;
00209   }
00210   else
00211   {
00212     try
00213     {
00214       this->soft_upper_limit = boost::lexical_cast<double>(soft_upper_limit_str);
00215     }
00216     catch (boost::bad_lexical_cast &e)
00217     {
00218       ROS_ERROR("soft_upper_limit value (%s) is not a float",soft_upper_limit_str);
00219       return false;
00220     }
00221   }
00222 
00223   // Get k_position_ safety "position" gain - not exactly position gain
00224   const char* k_position_str = config->Attribute("k_position");
00225   if (k_position_str == NULL)
00226   {
00227     ROS_DEBUG("joint safety: no k_position, using default value");
00228     this->k_position = 0;
00229   }
00230   else
00231   {
00232     try
00233     {
00234       this->k_position = boost::lexical_cast<double>(k_position_str);
00235     }
00236     catch (boost::bad_lexical_cast &e)
00237     {
00238       ROS_ERROR("k_position value (%s) is not a float",k_position_str);
00239       return false;
00240     }
00241   }
00242   // Get k_velocity_ safety velocity gain
00243   const char* k_velocity_str = config->Attribute("k_velocity");
00244   if (k_velocity_str == NULL)
00245   {
00246     ROS_ERROR("joint safety: no k_velocity");
00247     return false;
00248   }
00249   else
00250   {
00251     try
00252     {
00253       this->k_velocity = boost::lexical_cast<double>(k_velocity_str);
00254     }
00255     catch (boost::bad_lexical_cast &e)
00256     {
00257       ROS_ERROR("k_velocity value (%s) is not a float",k_velocity_str);
00258       return false;
00259     }
00260   }
00261 
00262   return true;
00263 }
00264 
00265 bool JointCalibration::initXml(TiXmlElement* config)
00266 {
00267   this->clear();
00268 
00269   // Get rising edge position
00270   const char* rising_position_str = config->Attribute("rising");
00271   if (rising_position_str == NULL)
00272   {
00273     ROS_DEBUG("joint calibration: no rising, using default value");
00274     this->rising.reset();
00275   }
00276   else
00277   {
00278     try
00279     {
00280       this->rising.reset(new double(boost::lexical_cast<double>(rising_position_str)));
00281     }
00282     catch (boost::bad_lexical_cast &e)
00283     {
00284       ROS_ERROR("risingvalue (%s) is not a float",rising_position_str);
00285       return false;
00286     }
00287   }
00288 
00289   // Get falling edge position
00290   const char* falling_position_str = config->Attribute("falling");
00291   if (falling_position_str == NULL)
00292   {
00293     ROS_DEBUG("joint calibration: no falling, using default value");
00294     this->falling.reset();
00295   }
00296   else
00297   {
00298     try
00299     {
00300       this->falling.reset(new double(boost::lexical_cast<double>(falling_position_str)));
00301     }
00302     catch (boost::bad_lexical_cast &e)
00303     {
00304       ROS_ERROR("fallingvalue (%s) is not a float",falling_position_str);
00305       return false;
00306     }
00307   }
00308 
00309   return true;
00310 }
00311 
00312 bool JointMimic::initXml(TiXmlElement* config)
00313 {
00314   this->clear();
00315 
00316   // Get name of joint to mimic
00317   const char* joint_name_str = config->Attribute("joint");
00318 
00319   if (joint_name_str == NULL)
00320   {
00321     ROS_ERROR("joint mimic: no mimic joint specified");
00322     //return false;
00323   }
00324   else
00325      this->joint_name = joint_name_str;
00326   
00327   // Get mimic multiplier
00328   const char* multiplier_str = config->Attribute("multiplier");
00329 
00330   if (multiplier_str == NULL)
00331   {
00332     ROS_DEBUG("joint mimic: no multiplier, using default value of 1");
00333     this->multiplier = 1;    
00334   }
00335   else
00336   {
00337     try
00338     {
00339       this->multiplier = boost::lexical_cast<double>(multiplier_str);
00340     }
00341     catch (boost::bad_lexical_cast &e)
00342     {
00343       ROS_ERROR("multiplier value (%s) is not a float",multiplier_str);
00344       return false;
00345     }
00346   }
00347 
00348   
00349   // Get mimic offset
00350   const char* offset_str = config->Attribute("offset");
00351   if (offset_str == NULL)
00352   {
00353     ROS_DEBUG("joint mimic: no offset, using default value of 0");
00354     this->offset = 0;
00355   }
00356   else
00357   {
00358     try
00359     {
00360       this->offset = boost::lexical_cast<double>(offset_str);
00361     }
00362     catch (boost::bad_lexical_cast &e)
00363     {
00364       ROS_ERROR("offset value (%s) is not a float",offset_str);
00365       return false;
00366     }
00367   }
00368 
00369   return true;
00370 }
00371 
00372 bool Joint::initXml(TiXmlElement* config)
00373 {
00374   this->clear();
00375 
00376   // Get Joint Name
00377   const char *name = config->Attribute("name");
00378   if (!name)
00379   {
00380     ROS_ERROR("unnamed joint found");
00381     return false;
00382   }
00383   this->name = name;
00384 
00385   // Get transform from Parent Link to Joint Frame
00386   TiXmlElement *origin_xml = config->FirstChildElement("origin");
00387   if (!origin_xml)
00388   {
00389     ROS_DEBUG("Joint '%s' missing origin tag under parent describing transform from Parent Link to Joint Frame, (using Identity transform).", this->name.c_str());
00390     this->parent_to_joint_origin_transform.clear();
00391   }
00392   else
00393   {
00394     if (!this->parent_to_joint_origin_transform.initXml(origin_xml))
00395     {
00396       ROS_ERROR("Malformed parent origin element for joint '%s'", this->name.c_str());
00397       this->parent_to_joint_origin_transform.clear();
00398       return false;
00399     }
00400   }
00401 
00402   // Get Parent Link
00403   TiXmlElement *parent_xml = config->FirstChildElement("parent");
00404   if (parent_xml)
00405   {
00406     const char *pname = parent_xml->Attribute("link");
00407     if (!pname)
00408       ROS_INFO("no parent link name specified for Joint link '%s'. this might be the root?", this->name.c_str());
00409     else
00410     {
00411       this->parent_link_name = std::string(pname);
00412 
00413     }
00414   }
00415 
00416   // Get Child Link
00417   TiXmlElement *child_xml = config->FirstChildElement("child");
00418   if (child_xml)
00419   {
00420     const char *pname = child_xml->Attribute("link");
00421     if (!pname)
00422       ROS_INFO("no child link name specified for Joint link '%s'.", this->name.c_str());
00423     else
00424     {
00425       this->child_link_name = std::string(pname);
00426 
00427     }
00428   }
00429 
00430   // Get Joint type
00431   const char* type_char = config->Attribute("type");
00432   if (!type_char)
00433   {
00434     ROS_ERROR("joint '%s' has no type, check to see if it's a reference.", this->name.c_str());
00435     return false;
00436   }
00437   std::string type_str = type_char;
00438   if (type_str == "planar")
00439   {
00440     type = PLANAR;
00441     ROS_WARN("Planar joints are deprecated in the URDF!\n");
00442   }
00443   else if (type_str == "floating")
00444   {
00445     type = FLOATING;
00446     ROS_WARN("Floating joints are deprecated in the URDF!\n");
00447   }
00448   else if (type_str == "revolute")
00449     type = REVOLUTE;
00450   else if (type_str == "continuous")
00451     type = CONTINUOUS;
00452   else if (type_str == "prismatic")
00453     type = PRISMATIC;
00454   else if (type_str == "fixed")
00455     type = FIXED;
00456   else
00457   {
00458     ROS_ERROR("Joint '%s' has no known type '%s'", this->name.c_str(), type_str.c_str());
00459     return false;
00460   }
00461 
00462   // Get Joint Axis
00463   if (this->type != FLOATING && this->type != FIXED)
00464   {
00465     // axis
00466     TiXmlElement *axis_xml = config->FirstChildElement("axis");
00467     if (!axis_xml){
00468       ROS_DEBUG("no axis elemement for Joint link '%s', defaulting to (1,0,0) axis", this->name.c_str());
00469       this->axis = Vector3(1.0, 0.0, 0.0);
00470     }
00471     else{
00472       if (!axis_xml->Attribute("xyz")){
00473         ROS_ERROR("no xyz attribute for axis element for Joint link '%s'", this->name.c_str());
00474       }
00475       else {
00476         if (!this->axis.init(axis_xml->Attribute("xyz")))
00477         {
00478           ROS_ERROR("Malformed axis element for joint '%s'", this->name.c_str());
00479           this->axis.clear();
00480           return false;
00481         }
00482       }
00483     }
00484   }
00485 
00486   // Get limit
00487   TiXmlElement *limit_xml = config->FirstChildElement("limit");
00488   if (limit_xml)
00489   {
00490     limits.reset(new JointLimits);
00491     if (!limits->initXml(limit_xml))
00492     {
00493       ROS_ERROR("Could not parse limit element for joint '%s'", this->name.c_str());
00494       limits.reset();
00495       return false;
00496     }
00497   }
00498   else if (this->type == REVOLUTE)
00499   {
00500     ROS_ERROR("Joint '%s' is of type REVOLUTE but it does not specify limits", this->name.c_str());
00501     return false;
00502   }
00503   else if (this->type == PRISMATIC)
00504   {
00505     ROS_INFO("Joint '%s' is of type PRISMATIC without limits", this->name.c_str());
00506     limits.reset();
00507   }
00508 
00509   // Get safety
00510   TiXmlElement *safety_xml = config->FirstChildElement("safety_controller");
00511   if (safety_xml)
00512   {
00513     safety.reset(new JointSafety);
00514     if (!safety->initXml(safety_xml))
00515     {
00516       ROS_ERROR("Could not parse safety element for joint '%s'", this->name.c_str());
00517       safety.reset();
00518       return false;
00519     }
00520   }
00521 
00522   // Get calibration
00523   TiXmlElement *calibration_xml = config->FirstChildElement("calibration");
00524   if (calibration_xml)
00525   {
00526     calibration.reset(new JointCalibration);
00527     if (!calibration->initXml(calibration_xml))
00528     {
00529       ROS_ERROR("Could not parse calibration element for joint  '%s'", this->name.c_str());
00530       calibration.reset();
00531       return false;
00532     }
00533   }
00534 
00535   // Get Joint Mimic
00536   TiXmlElement *mimic_xml = config->FirstChildElement("mimic");
00537   if (mimic_xml)
00538   {
00539     mimic.reset(new JointMimic);
00540     if (!mimic->initXml(mimic_xml))
00541     {
00542       ROS_ERROR("Could not parse mimic element for joint  '%s'", this->name.c_str());
00543       mimic.reset();
00544       return false;
00545     }
00546   }
00547 
00548   // Get Dynamics
00549   TiXmlElement *prop_xml = config->FirstChildElement("dynamics");
00550   if (prop_xml)
00551   {
00552     dynamics.reset(new JointDynamics);
00553     if (!dynamics->initXml(prop_xml))
00554     {
00555       ROS_ERROR("Could not parse joint_dynamics element for joint '%s'", this->name.c_str());
00556       dynamics.reset();
00557       return false;
00558     }
00559   }
00560 
00561   return true;
00562 }
00563 
00564 
00565 
00566 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


urdf_parser
Author(s): Wim Meeussen, John Hsu, Rosen Diankov
autogenerated on Mon Aug 19 2013 11:02:09