|
42 | 42 |
|
43 | 43 | #include <kdl/frames.hpp> |
44 | 44 |
|
45 | | -#include <tf2/impl/convert.h> |
| 45 | +#include <tf2/convert.h> |
46 | 46 |
|
47 | 47 | #include "tf2_eigen_kdl/visibility_control.h" |
48 | 48 |
|
@@ -97,94 +97,77 @@ void wrenchKDLToEigen(const KDL::Wrench & k, Eigen::Matrix<double, 6, 1> & e); |
97 | 97 | TF2_EIGEN_KDL_PUBLIC |
98 | 98 | void wrenchEigenToKDL(const Eigen::Matrix<double, 6, 1> & e, KDL::Wrench & k); |
99 | 99 |
|
100 | | -namespace impl |
101 | | -{ |
102 | | - |
103 | 100 | template<> |
104 | | -template<> |
105 | | -inline void Converter<false, false>::convert(const KDL::Rotation & a, Eigen::Quaterniond & b) |
| 101 | +void convert(const KDL::Rotation & a, Eigen::Quaterniond & b) |
106 | 102 | { |
107 | 103 | quaternionKDLToEigen(a, b); |
108 | 104 | } |
109 | 105 |
|
110 | 106 | template<> |
111 | | -template<> |
112 | | -inline void Converter<false, false>::convert(const Eigen::Quaterniond & a, KDL::Rotation & b) |
| 107 | +void convert(const Eigen::Quaterniond & a, KDL::Rotation & b) |
113 | 108 | { |
114 | 109 | quaternionEigenToKDL(a, b); |
115 | 110 | } |
116 | 111 |
|
117 | 112 | template<> |
118 | | -template<> |
119 | | -inline void Converter<false, false>::convert(const KDL::Frame & a, Eigen::Affine3d & b) |
| 113 | +void convert(const KDL::Frame & a, Eigen::Affine3d & b) |
120 | 114 | { |
121 | 115 | transformKDLToEigen(a, b); |
122 | 116 | } |
123 | 117 |
|
124 | 118 | template<> |
125 | | -template<> |
126 | | -inline void Converter<false, false>::convert(const KDL::Frame & a, Eigen::Isometry3d & b) |
| 119 | +void convert(const KDL::Frame & a, Eigen::Isometry3d & b) |
127 | 120 | { |
128 | 121 | transformKDLToEigen(a, b); |
129 | 122 | } |
130 | 123 |
|
131 | 124 | template<> |
132 | | -template<> |
133 | | -inline void Converter<false, false>::convert(const Eigen::Affine3d & a, KDL::Frame & b) |
| 125 | +void convert(const Eigen::Affine3d & a, KDL::Frame & b) |
134 | 126 | { |
135 | 127 | transformEigenToKDL(a, b); |
136 | 128 | } |
137 | 129 |
|
138 | 130 | template<> |
139 | | -template<> |
140 | | -inline void Converter<false, false>::convert(const Eigen::Isometry3d & a, KDL::Frame & b) |
| 131 | +void convert(const Eigen::Isometry3d & a, KDL::Frame & b) |
141 | 132 | { |
142 | 133 | transformEigenToKDL(a, b); |
143 | 134 | } |
144 | 135 |
|
145 | 136 | template<> |
146 | | -template<> |
147 | | -inline void Converter<false, false>::convert(const KDL::Twist & a, Eigen::Matrix<double, 6, 1> & b) |
| 137 | +void convert(const KDL::Twist & a, Eigen::Matrix<double, 6, 1> & b) |
148 | 138 | { |
149 | 139 | twistKDLToEigen(a, b); |
150 | 140 | } |
151 | 141 |
|
152 | 142 | template<> |
153 | | -template<> |
154 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Twist & b) |
| 143 | +void convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Twist & b) |
155 | 144 | { |
156 | 145 | twistEigenToKDL(a, b); |
157 | 146 | } |
158 | 147 |
|
159 | 148 | template<> |
160 | | -template<> |
161 | | -inline void Converter<false, false>::convert(const KDL::Vector & a, Eigen::Matrix<double, 3, 1> & b) |
| 149 | +void convert(const KDL::Vector & a, Eigen::Matrix<double, 3, 1> & b) |
162 | 150 | { |
163 | 151 | vectorKDLToEigen(a, b); |
164 | 152 | } |
165 | 153 |
|
166 | 154 | template<> |
167 | | -template<> |
168 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 3, 1> & a, KDL::Vector & b) |
| 155 | +void convert(const Eigen::Matrix<double, 3, 1> & a, KDL::Vector & b) |
169 | 156 | { |
170 | 157 | vectorEigenToKDL(a, b); |
171 | 158 | } |
172 | 159 |
|
173 | 160 | template<> |
174 | | -template<> |
175 | | -inline void Converter<false, false>::convert(const KDL::Wrench & a, Eigen::Matrix<double, 6, 1> & b) |
| 161 | +void convert(const KDL::Wrench & a, Eigen::Matrix<double, 6, 1> & b) |
176 | 162 | { |
177 | 163 | wrenchKDLToEigen(a, b); |
178 | 164 | } |
179 | 165 |
|
180 | 166 | template<> |
181 | | -template<> |
182 | | -inline void Converter<false, false>::convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Wrench & b) |
| 167 | +void convert(const Eigen::Matrix<double, 6, 1> & a, KDL::Wrench & b) |
183 | 168 | { |
184 | 169 | wrenchEigenToKDL(a, b); |
185 | 170 | } |
186 | | -} // namespace impl |
187 | | - |
188 | 171 | } // namespace tf2 |
189 | 172 |
|
190 | 173 | #endif // TF2_EIGEN_KDL__TF2_EIGEN_KDL_HPP_ |
0 commit comments