transmission_parser.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Open Source Robotics Foundation
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 Open Source Robotics Foundation
00018  *     nor the names of its contributors may be
00019  *     used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include <sstream>
00037 #include <transmission_interface/transmission_parser.h>
00038 
00039 namespace transmission_interface
00040 {
00041 
00042 bool TransmissionParser::parse(const std::string& urdf, std::vector<TransmissionInfo>& transmissions)
00043 {
00044   // initialize TiXmlDocument doc with a string
00045   TiXmlDocument doc;
00046   if (!doc.Parse(urdf.c_str()) && doc.Error())
00047   {
00048     ROS_ERROR("Can't parse transmissions. Invalid robot description.");
00049     return false;
00050   }
00051 
00052   // Find joints in transmission tags
00053   TiXmlElement *root = doc.RootElement();
00054 
00055   // Constructs the transmissions by parsing custom xml.
00056   TiXmlElement *trans_it = NULL;
00057   for (trans_it = root->FirstChildElement("transmission"); trans_it;
00058        trans_it = trans_it->NextSiblingElement("transmission"))
00059   {
00060     transmission_interface::TransmissionInfo transmission;
00061 
00062     // Transmission name
00063     if(trans_it->Attribute("name"))
00064     {
00065       transmission.name_ = trans_it->Attribute("name");
00066       if (transmission.name_.empty())
00067       {
00068         ROS_ERROR_STREAM_NAMED("parser","Empty name attribute specified for transmission.");
00069         continue;
00070       }
00071     }
00072     else
00073     {
00074       ROS_ERROR_STREAM_NAMED("parser","No name attribute specified for transmission.");
00075       continue;
00076     }
00077 
00078     // Transmission type
00079     TiXmlElement *type_child = trans_it->FirstChildElement("type");
00080     if(!type_child)
00081     {
00082       ROS_ERROR_STREAM_NAMED("parser","No type element found in transmission '"
00083         << transmission.name_ << "'.");
00084       continue;
00085     }
00086     if (!type_child->GetText())
00087     {
00088       ROS_ERROR_STREAM_NAMED("parser","Skipping empty type element in transmission '"
00089                              << transmission.name_ << "'.");
00090       continue;
00091     }
00092     transmission.type_ = type_child->GetText();
00093 
00094     // Load joints
00095     if(!parseJoints(trans_it, transmission.joints_))
00096     {
00097       ROS_ERROR_STREAM_NAMED("parser","Failed to load joints for transmission '"
00098         << transmission.name_ << "'.");
00099       continue;
00100     }
00101 
00102     // Load actuators
00103     if(!parseActuators(trans_it, transmission.actuators_))
00104     {
00105       ROS_ERROR_STREAM_NAMED("parser","Failed to load actuators for transmission '"
00106         << transmission.name_ << "'.");
00107       continue;
00108     }
00109 
00110     // Save loaded transmission
00111     transmissions.push_back(transmission);
00112 
00113   } // end for <transmission>
00114 
00115   if( transmissions.empty() )
00116   {
00117     ROS_DEBUG_STREAM_NAMED("parser", "No valid transmissions found.");
00118   }
00119 
00120   return true;
00121 }
00122 
00123 bool TransmissionParser::parseJoints(TiXmlElement *trans_it, std::vector<JointInfo>& joints)
00124 {
00125   // Loop through each available joint
00126   TiXmlElement *joint_it = NULL;
00127   for (joint_it = trans_it->FirstChildElement("joint"); joint_it;
00128        joint_it = joint_it->NextSiblingElement("joint"))
00129   {
00130     // Create new joint
00131     transmission_interface::JointInfo joint;
00132 
00133     // Joint name
00134     if(joint_it->Attribute("name"))
00135     {
00136       joint.name_ = joint_it->Attribute("name");
00137       if (joint.name_.empty())
00138       {
00139         ROS_ERROR_STREAM_NAMED("parser","Empty name attribute specified for joint.");
00140         continue;
00141       }
00142     }
00143     else
00144     {
00145       ROS_ERROR_STREAM_NAMED("parser","No name attribute specified for joint.");
00146       return false;
00147     }
00148 
00149     // Hardware interfaces (required)
00150     TiXmlElement *hw_iface_it = NULL;
00151     for (hw_iface_it = joint_it->FirstChildElement("hardwareInterface"); hw_iface_it;
00152          hw_iface_it = hw_iface_it->NextSiblingElement("hardwareInterface"))
00153     {
00154       if(!hw_iface_it) {continue;}
00155       if (!hw_iface_it->GetText())
00156       {
00157         ROS_DEBUG_STREAM_NAMED("parser","Skipping empty hardware interface element in joint '"
00158                                << joint.name_ << "'.");
00159         continue;
00160       }
00161       const std::string hw_iface_name = hw_iface_it->GetText();
00162       joint.hardware_interfaces_.push_back(hw_iface_name);
00163     }
00164     if (joint.hardware_interfaces_.empty())
00165     {
00166       ROS_ERROR_STREAM_NAMED("parser","No valid hardware interface element found in joint '"
00167         << joint.name_ << "'.");
00168       continue;
00169     }
00170 
00171     // Joint xml element
00172     std::stringstream ss;
00173     ss << *joint_it;
00174     joint.xml_element_ = ss.str();
00175 
00176     // Add joint to vector
00177     joints.push_back(joint);
00178   }
00179 
00180   if(joints.empty())
00181   {
00182     ROS_DEBUG_NAMED("parser","No valid joint element found.");
00183     return false;
00184   }
00185 
00186   return true;
00187 }
00188 
00189 bool TransmissionParser::parseActuators(TiXmlElement *trans_it, std::vector<ActuatorInfo>& actuators)
00190 {
00191   // Loop through each available actuator
00192   TiXmlElement *actuator_it = NULL;
00193   for (actuator_it = trans_it->FirstChildElement("actuator"); actuator_it;
00194        actuator_it = actuator_it->NextSiblingElement("actuator"))
00195   {
00196     // Create new actuator
00197     transmission_interface::ActuatorInfo actuator;
00198 
00199     // Actuator name
00200     if(actuator_it->Attribute("name"))
00201     {
00202       actuator.name_ = actuator_it->Attribute("name");
00203       if (actuator.name_.empty())
00204       {
00205         ROS_ERROR_STREAM_NAMED("parser","Empty name attribute specified for actuator.");
00206         continue;
00207       }
00208     }
00209     else
00210     {
00211       ROS_ERROR_STREAM_NAMED("parser","No name attribute specified for actuator.");
00212       return false;
00213     }
00214 
00215     // Hardware interfaces (optional)
00216     TiXmlElement *hw_iface_it = NULL;
00217     for (hw_iface_it = actuator_it->FirstChildElement("hardwareInterface"); hw_iface_it;
00218          hw_iface_it = hw_iface_it->NextSiblingElement("hardwareInterface"))
00219     {
00220       if(!hw_iface_it) {continue;}
00221       if (!hw_iface_it->GetText())
00222       {
00223         ROS_DEBUG_STREAM_NAMED("parser","Skipping empty hardware interface element in actuator '"
00224                                << actuator.name_ << "'.");
00225         continue;
00226       }
00227       const std::string hw_iface_name = hw_iface_it->GetText();
00228       actuator.hardware_interfaces_.push_back(hw_iface_name);
00229     }
00230     if (actuator.hardware_interfaces_.empty())
00231     {
00232       ROS_DEBUG_STREAM_NAMED("parser","Optional: No valid hardware interface element found in actuator '"
00233         << actuator.name_ << "'.");
00234       // continue; // NOTE: Hardware interface is optional, so we keep on going
00235     }
00236 
00237     // Actuator xml element
00238     std::stringstream ss;
00239     ss << *actuator_it;
00240     actuator.xml_element_ = ss.str();
00241 
00242     // Add actuator to vector
00243     actuators.push_back(actuator);
00244   }
00245 
00246   if(actuators.empty())
00247   {
00248     ROS_DEBUG_NAMED("parser","No valid actuator element found.");
00249     return false;
00250   }
00251 
00252   return true;
00253 }
00254 
00255 } // namespace


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:09:31