15 #ifndef BELUGA_ROS_TF2_SOPHUS_HPP
16 #define BELUGA_ROS_TF2_SOPHUS_HPP
21 #if BELUGA_ROS_VERSION == 2
22 #include <tf2_eigen/tf2_eigen.hpp>
23 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
24 #elif BELUGA_ROS_VERSION == 1
28 #error BELUGA_ROS_VERSION is not defined or invalid
55 template <
class Scalar>
57 const double theta = in.
so2().log();
61 out.orientation.w = std::cos(theta / 2.);
62 out.orientation.x = 0;
63 out.orientation.y = 0;
64 out.orientation.z = std::sin(theta / 2.);
78 template <
class Scalar>
97 template <
class Scalar>
99 auto msg = beluga_ros::msg::Transform{};
100 const double theta = in.
so2().log();
103 msg.translation.z = 0;
104 msg.rotation.w = std::cos(theta / 2.);
107 msg.rotation.z = std::sin(theta / 2.);
118 template <
class Scalar>
120 auto msg = beluga_ros::msg::Transform{};
138 template <
class Scalar>
154 template <
class Scalar>
157 static_cast<Scalar
>(msg.translation.x),
158 static_cast<Scalar
>(msg.translation.y),
159 static_cast<Scalar
>(msg.translation.z),
162 static_cast<Scalar
>(msg.rotation.w),
163 static_cast<Scalar
>(msg.rotation.x),
164 static_cast<Scalar
>(msg.rotation.y),
165 static_cast<Scalar
>(msg.rotation.z),
176 template <
class Scalar>
179 static_cast<Scalar
>(msg.position.x),
180 static_cast<Scalar
>(msg.position.y),
192 template <
class Scalar>
195 static_cast<Scalar
>(msg.position.x),
196 static_cast<Scalar
>(msg.position.y),
197 static_cast<Scalar
>(msg.position.z),
200 static_cast<Scalar
>(msg.orientation.w),
201 static_cast<Scalar
>(msg.orientation.x),
202 static_cast<Scalar
>(msg.orientation.y),
203 static_cast<Scalar
>(msg.orientation.z),
213 template <
template <
typename, std::
size_t>
class Array,
typename Scalar>
216 out[0] = in.coeff(0, 0);
217 out[1] = in.coeff(0, 1);
218 out[5] = in.coeff(0, 2);
219 out[6] = in.coeff(1, 0);
220 out[7] = in.coeff(1, 1);
221 out[11] = in.coeff(1, 2);
222 out[30] = in.coeff(2, 0);
223 out[31] = in.coeff(2, 1);
224 out[35] = in.coeff(2, 2);
234 template <
template <
typename, std::
size_t>
class Array,
typename Scalar>
236 out.coeffRef(0, 0) = in[0];
237 out.coeffRef(0, 1) = in[1];
238 out.coeffRef(0, 2) = in[5];
239 out.coeffRef(1, 0) = in[6];
240 out.coeffRef(1, 1) = in[7];
241 out.coeffRef(1, 2) = in[11];
242 out.coeffRef(2, 0) = in[30];
243 out.coeffRef(2, 1) = in[31];
244 out.coeffRef(2, 2) = in[35];
254 template <
class Scalar>
260 template <
class Scalar>
266 template <
class Scalar>
272 template <
class Scalar>
278 template <
class Scalar>
284 template <
class Scalar>
291 #endif // BELUGA_ROS_TF2_SOPHUS_HPP