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 <transmission_interface/transmission_parser.h>
00037 
00038 namespace transmission_interface
00039 {
00040 
00041 bool TransmissionParser::parse(const std::string& urdf, std::vector<TransmissionInfo>& transmissions)
00042 {
00043   // initialize TiXmlDocument doc with a string
00044   TiXmlDocument doc;
00045   if (!doc.Parse(urdf.c_str()) && doc.Error())
00046   {
00047     ROS_ERROR("Could not load the gazebo_ros_control plugin's"
00048       " configuration file: %s\n", urdf.c_str());
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     }
00067     else
00068     {
00069       ROS_ERROR_STREAM_NAMED("parser","No name attribute for transmission tag!");
00070       continue;
00071     }
00072 
00073     // Transmission type
00074     TiXmlElement *type_child = trans_it->FirstChildElement("type");
00075     if(!type_child)
00076     {
00077       ROS_ERROR_STREAM_NAMED("parser","No type element found for transmission "
00078         << transmission.name_);
00079       continue;
00080     }
00081     transmission.type_ = type_child->GetText();
00082     if(transmission.type_.empty())
00083     {
00084       ROS_ERROR_STREAM_NAMED("parser","No type string found for transmission "
00085         << transmission.name_);
00086       continue;
00087     }
00088 
00089     // Load joints
00090     if(!parseJoints(trans_it, transmission.joints_))
00091     {
00092       ROS_ERROR_STREAM_NAMED("parser","Failed to load joints for transmission "
00093         << transmission.name_);
00094       continue;
00095     }
00096 
00097     // Load actuators
00098     if(!parseActuators(trans_it, transmission.actuators_))
00099     {
00100       ROS_ERROR_STREAM_NAMED("parser","Failed to load actuators for transmission "
00101         << transmission.name_);
00102       continue;
00103     }
00104 
00105     // Save loaded transmission
00106     transmissions.push_back(transmission);
00107 
00108   } // end for <transmission>
00109 
00110   if( transmissions.empty() )
00111   {
00112     ROS_DEBUG_STREAM_NAMED("parser","No tranmissions found.");
00113   }
00114 
00115   return true;
00116 }
00117 
00118 bool TransmissionParser::parseJoints(TiXmlElement *trans_it, std::vector<JointInfo>& joints)
00119 {
00120   // Loop through each available joint
00121   TiXmlElement *joint_it = NULL;
00122   for (joint_it = trans_it->FirstChildElement("joint"); joint_it;
00123        joint_it = joint_it->NextSiblingElement("joint"))
00124   {
00125     // Create new joint
00126     transmission_interface::JointInfo joint;
00127 
00128     // Joint xml element
00129     joint.xml_element_ = joint_it;
00130 
00131     // Joint name
00132     if(joint_it->Attribute("name"))
00133     {
00134       joint.name_ = joint_it->Attribute("name");
00135     }
00136     else
00137     {
00138       ROS_ERROR_STREAM_NAMED("parser","No name attribute for joint");
00139       return false;
00140     }
00141 
00142     // \todo: implement other generic joint properties
00143 
00144     // Add joint to vector
00145     joints.push_back(joint);
00146   }
00147 
00148   if(joints.empty())
00149   {
00150     ROS_ERROR_STREAM_NAMED("parser","No joint element found");
00151     return false;
00152   }
00153 
00154   return true;
00155 }
00156 
00157 bool TransmissionParser::parseActuators(TiXmlElement *trans_it, std::vector<ActuatorInfo>& actuators)
00158 {
00159   // Loop through each available actuator
00160   TiXmlElement *actuator_it = NULL;
00161   for (actuator_it = trans_it->FirstChildElement("actuator"); actuator_it;
00162        actuator_it = actuator_it->NextSiblingElement("actuator"))
00163   {
00164     // Create new actuator
00165     transmission_interface::ActuatorInfo actuator;
00166 
00167     // Actuator xml element
00168     actuator.xml_element_ = actuator_it;
00169 
00170     // Actuator name
00171     if(actuator_it->Attribute("name"))
00172     {
00173       actuator.name_ = actuator_it->Attribute("name");
00174     }
00175     else
00176     {
00177       ROS_ERROR_STREAM_NAMED("parser","No name attribute for actuator");
00178       return false;
00179     }
00180 
00181     // Hardware interface
00182     TiXmlElement *hardware_interface_child = actuator_it->FirstChildElement("hardwareInterface");
00183     if(!hardware_interface_child)
00184     {
00185       ROS_ERROR_STREAM_NAMED("parser","No hardware interface element found for actuator '"
00186         << actuator.name_ << "'");
00187       continue;
00188     }
00189     actuator.hardware_interface_ = hardware_interface_child->GetText();
00190     if(actuator.hardware_interface_.empty())
00191     {
00192       ROS_ERROR_STREAM_NAMED("parser","No hardware interface string found for actuator '"
00193         << actuator.name_ << "'");
00194       continue;
00195     }
00196 
00197     // \todo: implement other generic actuator properties
00198 
00199     // Add actuator to vector
00200     actuators.push_back(actuator);
00201   }
00202 
00203   if(actuators.empty())
00204   {
00205     ROS_ERROR_STREAM_NAMED("parser","No actuator element found");
00206     return false;
00207   }
00208 
00209   return true;
00210 }
00211 
00212 } // namespace


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Aug 28 2015 12:36:26