transmission_loader.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #ifndef TRANSMISSION_INTERFACE_TRANSMISSION_LOADER_H
31 #define TRANSMISSION_INTERFACE_TRANSMISSION_LOADER_H
32 
33 // C++ standard
34 #include <algorithm>
35 #include <limits>
36 #include <sstream>
37 #include <string>
38 #include <vector>
39 
40 // Boost
41 #include <boost/foreach.hpp>
42 #include <boost/shared_ptr.hpp>
43 
44 // TinyXML
45 #include <tinyxml.h>
46 
47 // ros_control
51 
55 
56 namespace transmission_interface
57 {
58 
65 {
66 public:
67 
68  virtual ~TransmissionLoader() {}
69 
70  virtual TransmissionSharedPtr load(const TransmissionInfo& transmission_info) = 0;
71 
72 protected:
74  {
78  };
79 
80  static bool checkActuatorDimension(const TransmissionInfo& transmission_info, const unsigned int expected_dim)
81  {
82  const unsigned int dim = transmission_info.actuators_.size();
83  if (expected_dim != dim)
84  {
85  ROS_ERROR_STREAM_NAMED("parser", "Invalid description for transmission '" << transmission_info.name_ <<
86  "' of type '" << transmission_info.type_ <<
87  "'. Expected " << expected_dim << " actuators, got " << dim << ".");
88  return false;
89  }
90  return true;
91  }
92 
93  static bool checkJointDimension(const TransmissionInfo& transmission_info, const unsigned int expected_dim)
94  {
95  const unsigned int dim = transmission_info.joints_.size();
96  if (expected_dim != dim)
97  {
98  ROS_ERROR_STREAM_NAMED("parser", "Invalid description for transmission '" << transmission_info.name_ <<
99  "' of type '" << transmission_info.type_ <<
100  "'. Expected " << expected_dim << " joints, got " << dim << ".");
101  return false;
102  }
103  return true;
104  }
105 
106  static TiXmlElement loadXmlElement(const std::string& element_str)
107  {
108  TiXmlElement element("");
109  std::stringstream element_stream;
110  element_stream << element_str;
111  element_stream >> element;
112  return element;
113  }
114 
115  static ParseStatus getActuatorReduction(const TiXmlElement& parent_el,
116  const std::string& actuator_name,
117  const std::string& transmission_name,
118  bool required,
119  double& reduction);
120 
121  static ParseStatus getJointReduction(const TiXmlElement& parent_el,
122  const std::string& joint_name,
123  const std::string& transmission_name,
124  bool required,
125  double& reduction);
126 
127  static ParseStatus getJointOffset(const TiXmlElement& parent_el,
128  const std::string& joint_name,
129  const std::string& transmission_name,
130  bool required,
131  double& offset);
132 
133  static ParseStatus getActuatorRole(const TiXmlElement& parent_el,
134  const std::string& actuator_name,
135  const std::string& transmission_name,
136  bool required,
137  std::string& role);
138 
139  static ParseStatus getJointRole(const TiXmlElement& parent_el,
140  const std::string& joint_name,
141  const std::string& transmission_name,
142  bool required,
143  std::string& role);
144 };
145 
147 
148 } // namespace
149 
150 #endif // header guard
boost::shared_ptr< TransmissionLoader > TransmissionLoaderSharedPtr
static TiXmlElement loadXmlElement(const std::string &element_str)
#define ROS_ERROR_STREAM_NAMED(name, args)
Abstract interface for loading transmission instances from configuration data.
Contains semantic info about a given transmission loaded from XML (URDF)
static ParseStatus getActuatorReduction(const TiXmlElement &parent_el, const std::string &actuator_name, const std::string &transmission_name, bool required, double &reduction)
Structs to hold tranmission data loaded straight from XML (URDF).
static ParseStatus getActuatorRole(const TiXmlElement &parent_el, const std::string &actuator_name, const std::string &transmission_name, bool required, std::string &role)
static bool checkActuatorDimension(const TransmissionInfo &transmission_info, const unsigned int expected_dim)
static ParseStatus getJointRole(const TiXmlElement &parent_el, const std::string &joint_name, const std::string &transmission_name, bool required, std::string &role)
virtual TransmissionSharedPtr load(const TransmissionInfo &transmission_info)=0
static ParseStatus getJointReduction(const TiXmlElement &parent_el, const std::string &joint_name, const std::string &transmission_name, bool required, double &reduction)
std::vector< ActuatorInfo > actuators_
static ParseStatus getJointOffset(const TiXmlElement &parent_el, const std::string &joint_name, const std::string &transmission_name, bool required, double &offset)
static bool checkJointDimension(const TransmissionInfo &transmission_info, const unsigned int expected_dim)


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:17