transmission_loader.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 // Boost
00029 #include <boost/lexical_cast.hpp>
00030 
00031 // ros_control
00032 #include <transmission_interface/transmission_loader.h>
00033 
00034 
00035 namespace transmission_interface
00036 {
00037 
00038 TransmissionLoader::ParseStatus
00039 TransmissionLoader::getActuatorReduction(const TiXmlElement& parent_el,
00040                                          const std::string&  actuator_name,
00041                                          const std::string&  transmission_name,
00042                                          bool                required,
00043                                          double&             reduction)
00044 {
00045   // Get XML element
00046   const TiXmlElement* reduction_el = parent_el.FirstChildElement("mechanicalReduction");
00047   if(!reduction_el)
00048   {
00049     if (required)
00050     {
00051       ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00052                              "' does not specify the required <mechanicalReduction> element.");
00053     }
00054     else
00055     {
00056       ROS_DEBUG_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00057                              "' does not specify the optional <mechanicalReduction> element.");
00058     }
00059     return NO_DATA;
00060   }
00061 
00062   // Cast to number
00063   try {reduction = boost::lexical_cast<double>(reduction_el->GetText());}
00064   catch (const boost::bad_lexical_cast&)
00065   {
00066     ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00067                            "' specifies the <mechanicalReduction> element, but is not a number.");
00068     return BAD_TYPE;
00069   }
00070   return SUCCESS;
00071 }
00072 
00073 TransmissionLoader::ParseStatus
00074 TransmissionLoader::getJointReduction(const TiXmlElement& parent_el,
00075                                       const std::string&  joint_name,
00076                                       const std::string&  transmission_name,
00077                                       bool                required,
00078                                       double&             reduction)
00079 {
00080   // Get XML element
00081   const TiXmlElement* reduction_el = parent_el.FirstChildElement("mechanicalReduction");
00082   if(!reduction_el)
00083   {
00084     if (required)
00085     {
00086       ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00087                              "' does not specify the required <mechanicalReduction> element.");
00088     }
00089     else
00090     {
00091       ROS_DEBUG_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00092                              "' does not specify the optional <mechanicalReduction> element.");
00093     }
00094     return NO_DATA;
00095   }
00096 
00097   // Cast to number
00098   try {reduction = boost::lexical_cast<double>(reduction_el->GetText());}
00099   catch (const boost::bad_lexical_cast&)
00100   {
00101     ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00102                            "' specifies the <mechanicalReduction> element, but is not a number.");
00103     return BAD_TYPE;
00104   }
00105   return SUCCESS;
00106 }
00107 
00108 TransmissionLoader::ParseStatus
00109 TransmissionLoader::getJointOffset(const TiXmlElement& parent_el,
00110                                    const std::string&  joint_name,
00111                                    const std::string&  transmission_name,
00112                                    bool                required,
00113                                    double&             offset)
00114 {
00115   // Get XML element
00116   const TiXmlElement* offset_el = parent_el.FirstChildElement("offset");
00117   if(!offset_el)
00118   {
00119     if (required)
00120     {
00121       ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00122                              "' does not specify the required <offset> element.");
00123     }
00124     else
00125     {
00126       ROS_DEBUG_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00127                              "' does not specify the optional <offset> element.");
00128     }
00129     return NO_DATA;
00130   }
00131 
00132   // Cast to number
00133   try {offset = boost::lexical_cast<double>(offset_el->GetText());}
00134   catch (const boost::bad_lexical_cast&)
00135   {
00136     ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00137                            "' specifies the <offset> element, but is not a number.");
00138     return BAD_TYPE;
00139   }
00140   return SUCCESS;
00141 }
00142 
00143 TransmissionLoader::ParseStatus
00144 TransmissionLoader::getActuatorRole(const TiXmlElement& parent_el,
00145                                     const std::string&  actuator_name,
00146                                     const std::string&  transmission_name,
00147                                     bool                required,
00148                                     std::string&        role)
00149 {
00150   // Get XML element
00151   const TiXmlElement* role_el = parent_el.FirstChildElement("role");
00152   if(!role_el)
00153   {
00154     if (required)
00155     {
00156       ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00157                              "' does not specify the required <role> element.");
00158     }
00159     else
00160     {
00161       ROS_DEBUG_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00162                              "' does not specify the optional <offset> element.");
00163     }
00164     return NO_DATA;
00165   }
00166 
00167   // Cast to number
00168   if (!role_el->GetText())
00169   {
00170     if (required)
00171     {
00172       ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00173                              "' specifies an empty <role> element.");
00174     }
00175     else
00176     {
00177       ROS_DEBUG_STREAM_NAMED("parser", "Actuator '" << actuator_name << "' of transmission '" << transmission_name <<
00178                              "' specifies an empty <role> element.");
00179     }
00180     return NO_DATA;
00181   }
00182   role = role_el->GetText();
00183 
00184   return SUCCESS;
00185 }
00186 
00187 TransmissionLoader::ParseStatus
00188 TransmissionLoader::getJointRole(const TiXmlElement& parent_el,
00189                                  const std::string&  joint_name,
00190                                  const std::string&  transmission_name,
00191                                  bool                required,
00192                                  std::string&        role)
00193 {
00194   // Get XML element
00195   const TiXmlElement* role_el = parent_el.FirstChildElement("role");
00196   if(!role_el)
00197   {
00198     if (required)
00199     {
00200       ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00201                              "' does not specify the required <role> element.");
00202     }
00203     else
00204     {
00205       ROS_DEBUG_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00206                              "' does not specify the optional <offset> element.");
00207     }
00208     return NO_DATA;
00209   }
00210 
00211   // Cast to number
00212   if (!role_el->GetText())
00213   {
00214     if (required)
00215     {
00216       ROS_ERROR_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00217                              "' specifies an empty <role> element.");
00218     }
00219     else
00220     {
00221       ROS_DEBUG_STREAM_NAMED("parser", "Joint '" << joint_name << "' of transmission '" << transmission_name <<
00222                              "' specifies an empty <role> element.");
00223     }
00224     return NO_DATA;
00225   }
00226   role = role_el->GetText();
00227 
00228   return SUCCESS;
00229 }
00230 
00231 } // namespace


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