transmission_loader.h
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 
00029 
00030 #ifndef TRANSMISSION_INTERFACE_TRANSMISSION_LOADER_H
00031 #define TRANSMISSION_INTERFACE_TRANSMISSION_LOADER_H
00032 
00033 // C++ standard
00034 #include <algorithm>
00035 #include <limits>
00036 #include <sstream>
00037 #include <string>
00038 #include <vector>
00039 
00040 // Boost
00041 #include <boost/foreach.hpp>
00042 #include <boost/shared_ptr.hpp>
00043 
00044 // TinyXML
00045 #include <tinyxml.h>
00046 
00047 // ros_control
00048 #include <hardware_interface/actuator_command_interface.h>
00049 #include <hardware_interface/joint_command_interface.h>
00050 #include <hardware_interface/robot_hw.h>
00051 
00052 #include <transmission_interface/robot_transmissions.h>
00053 #include <transmission_interface/transmission_info.h>
00054 #include <transmission_interface/transmission.h>
00055 
00056 namespace transmission_interface
00057 {
00058 
00064 class TransmissionLoader
00065 {
00066 public:
00067 
00068   virtual ~TransmissionLoader() {}
00069 
00070   typedef boost::shared_ptr<Transmission> TransmissionPtr;
00071   virtual TransmissionPtr load(const TransmissionInfo& transmission_info) = 0;
00072 
00073 protected:
00074   enum ParseStatus
00075   {
00076     SUCCESS,
00077     NO_DATA,
00078     BAD_TYPE
00079   };
00080 
00081   static bool checkActuatorDimension(const TransmissionInfo& transmission_info, const unsigned int expected_dim)
00082   {
00083     const unsigned int dim = transmission_info.actuators_.size();
00084     if (expected_dim != dim)
00085     {
00086       ROS_ERROR_STREAM_NAMED("parser", "Invalid description for transmission '" << transmission_info.name_ <<
00087                              "' of type '" << transmission_info.type_ <<
00088                              "'. Expected " << expected_dim << " actuators, got " << dim << ".");
00089       return false;
00090     }
00091     return true;
00092   }
00093 
00094   static bool checkJointDimension(const TransmissionInfo& transmission_info, const unsigned int expected_dim)
00095   {
00096     const unsigned int dim = transmission_info.joints_.size();
00097     if (expected_dim != dim)
00098     {
00099       ROS_ERROR_STREAM_NAMED("parser", "Invalid description for transmission '" << transmission_info.name_ <<
00100                              "' of type '" << transmission_info.type_ <<
00101                              "'. Expected " << expected_dim << " joints, got " << dim << ".");
00102       return false;
00103     }
00104     return true;
00105   }
00106 
00107   static TiXmlElement loadXmlElement(const std::string& element_str)
00108   {
00109     TiXmlElement element("");
00110     std::stringstream element_stream;
00111     element_stream << element_str;
00112     element_stream >> element;
00113     return element;
00114   }
00115 
00116   static ParseStatus getActuatorReduction(const TiXmlElement& parent_el,
00117                                           const std::string&  actuator_name,
00118                                           const std::string&  transmission_name,
00119                                           bool                required,
00120                                           double&             reduction);
00121 
00122   static ParseStatus getJointReduction(const TiXmlElement& parent_el,
00123                                        const std::string&  joint_name,
00124                                        const std::string&  transmission_name,
00125                                        bool                required,
00126                                        double&             reduction);
00127 
00128   static ParseStatus getJointOffset(const TiXmlElement& parent_el,
00129                                     const std::string&  joint_name,
00130                                     const std::string&  transmission_name,
00131                                     bool                required,
00132                                     double&             offset);
00133 
00134   static ParseStatus getActuatorRole(const TiXmlElement& parent_el,
00135                                      const std::string&  actuator_name,
00136                                      const std::string&  transmission_name,
00137                                      bool                required,
00138                                      std::string&        role);
00139 
00140   static ParseStatus getJointRole(const TiXmlElement& parent_el,
00141                                   const std::string&  joint_name,
00142                                   const std::string&  transmission_name,
00143                                   bool                required,
00144                                   std::string&        role);
00145 };
00146 
00147 } // namespace
00148 
00149 #endif // header guard


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:10