|
55 | 55 |
|
56 | 56 | #include "kdl/frames.hpp" |
57 | 57 |
|
58 | | -#include "tf2/impl/convert.h" |
| 58 | +#include "tf2/convert.h" |
59 | 59 |
|
60 | 60 | #include "tf2_eigen_kdl/visibility_control.h" |
61 | 61 |
|
@@ -110,94 +110,77 @@ void wrenchKDLToEigen(const KDL::Wrench & k, Eigen::Matrix<double, 6, 1> & e); |
110 | 110 | TF2_EIGEN_KDL_PUBLIC |
111 | 111 | void wrenchEigenToKDL(const Eigen::Matrix<double, 6, 1> & e, KDL::Wrench & k); |
112 | 112 |
|
113 | | -namespace impl |
114 | | -{ |
115 | | - |
116 | 113 | template<> |
117 | | -template<> |
118 | | -inline void Converter<false, false>::convert(const KDL::Rotation & a, Eigen::Quaterniond & b) |
| 114 | +void convert(const KDL::Rotation & a, Eigen::Quaterniond & b) |
119 | 115 | { |
120 | 116 | quaternionKDLToEigen(a, b); |
121 | 117 | } |
122 | 118 |
|
123 | 119 | template<> |
124 | | -template<> |
125 | | -inline void Converter<false, false>::convert(const Eigen::Quaterniond & a, KDL::Rotation & b) |
| 120 | +void convert(const Eigen::Quaterniond & a, KDL::Rotation & b) |
126 | 121 | { |
127 | 122 | quaternionEigenToKDL(a, b); |
128 | 123 | } |
129 | 124 |
|
130 | 125 | template<> |
131 | | -template<> |
132 | | -inline void Converter<false, false>::convert(const KDL::Frame & a, Eigen::Affine3d & b) |
| 126 | +void convert(const KDL::Frame & a, Eigen::Affine3d & b) |
133 | 127 | { |
134 | 128 | transformKDLToEigen(a, b); |
135 | 129 | } |
136 | 130 |
|
137 | 131 | template<> |
138 | | -template<> |
139 | | -inline void Converter<false, false>::convert(const KDL::Frame & a, Eigen::Isometry3d & b) |
| 132 | +void convert(const KDL::Frame & a, Eigen::Isometry3d & b) |
140 | 133 | { |
141 | 134 | transformKDLToEigen(a, b); |
142 | 135 | } |
143 | 136 |
|
144 | 137 | template<> |
145 | | -template<> |
146 | | -inline void Converter<false, false>::convert(const Eigen::Affine3d & a, KDL::Frame & b) |
| 138 | +void convert(const Eigen::Affine3d & a, KDL::Frame & b) |
147 | 139 | { |
148 | 140 | transformEigenToKDL(a, b); |
149 | 141 | } |
150 | 142 |
|
151 | 143 | template<> |
152 | | -template<> |
153 | | -inline void Converter<false, false>::convert(const Eigen::Isometry3d & a, KDL::Frame & b) |
| 144 | +void convert(const Eigen::Isometry3d & a, KDL::Frame & b) |
154 | 145 | { |
155 | 146 | transformEigenToKDL(a, b); |
156 | 147 | } |
157 | 148 |
|
158 | 149 | template<> |
159 | | -template<> |
160 | | -inline void Converter<false, false>::convert(const KDL::Twist & a, Eigen::Matrix<double, 6, 1> & b) |
| 150 | +void convert(const KDL::Twist & a, Eigen::Matrix<double, 6, 1> & b) |
161 | 151 | { |
162 | 152 | twistKDLToEigen(a, b); |
163 | 153 | } |
164 | 154 |
|
165 | 155 | template<> |
166 | | -template<> |
167 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Twist & b) |
| 156 | +void convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Twist & b) |
168 | 157 | { |
169 | 158 | twistEigenToKDL(a, b); |
170 | 159 | } |
171 | 160 |
|
172 | 161 | template<> |
173 | | -template<> |
174 | | -inline void Converter<false, false>::convert(const KDL::Vector & a, Eigen::Matrix<double, 3, 1> & b) |
| 162 | +void convert(const KDL::Vector & a, Eigen::Matrix<double, 3, 1> & b) |
175 | 163 | { |
176 | 164 | vectorKDLToEigen(a, b); |
177 | 165 | } |
178 | 166 |
|
179 | 167 | template<> |
180 | | -template<> |
181 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 3, 1> & a, KDL::Vector & b) |
| 168 | +void convert(const Eigen::Matrix<double, 3, 1> & a, KDL::Vector & b) |
182 | 169 | { |
183 | 170 | vectorEigenToKDL(a, b); |
184 | 171 | } |
185 | 172 |
|
186 | 173 | template<> |
187 | | -template<> |
188 | | -inline void Converter<false, false>::convert(const KDL::Wrench & a, Eigen::Matrix<double, 6, 1> & b) |
| 174 | +void convert(const KDL::Wrench & a, Eigen::Matrix<double, 6, 1> & b) |
189 | 175 | { |
190 | 176 | wrenchKDLToEigen(a, b); |
191 | 177 | } |
192 | 178 |
|
193 | 179 | template<> |
194 | | -template<> |
195 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Wrench & b) |
| 180 | +void convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Wrench & b) |
196 | 181 | { |
197 | 182 | wrenchEigenToKDL(a, b); |
198 | 183 | } |
199 | | -} // namespace impl |
200 | | - |
201 | 184 | } // namespace tf2 |
202 | 185 |
|
203 | 186 | #endif // TF2_EIGEN_KDL__TF2_EIGEN_KDL_HPP_ |
0 commit comments