3434*
3535* Author: Eitan Marder-Eppstein
3636*********************************************************************/
37+
38+ #include < geometry_msgs/msg/vector3_stamped.hpp>
3739#include < gtest/gtest.h>
3840#include < tf2/convert.h>
3941#include < tf2_eigen/tf2_eigen.hpp>
4042#include < tf2_bullet/tf2_bullet.hpp>
4143#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
4244#include < tf2_kdl/tf2_kdl.hpp>
4345
46+
47+ // test of tf2 type traits
48+ static_assert (
49+ !tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3>::value,
50+ " MessageHasStdHeader traits error" );
51+ static_assert (
52+ tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3Stamped>::value,
53+ " MessageHasStdHeader traits error" );
54+
55+ namespace
56+ {
57+ struct MyPODMessage
58+ {
59+ int header;
60+ };
61+
62+ template <typename Alloc>
63+ struct MyAllocMessage
64+ {
65+ int header;
66+ };
67+
68+ static_assert (
69+ !tf2::impl::MessageHasStdHeader<MyPODMessage>::value,
70+ " MessageHasStdHeader traits error" );
71+
72+ template <typename T>
73+ struct MyAllocator
74+ {
75+ using value_type = T;
76+ using size_type = unsigned int ;
77+ T * allocate (size_type);
78+ void deallocate (T *, size_type);
79+ template <class U >
80+ struct rebind { typedef MyAllocator<U> other; };
81+ };
82+ using MyVec = geometry_msgs::msg::Vector3_<MyAllocator<void >>;
83+ using MyVecStamped = geometry_msgs::msg::Vector3Stamped_<MyAllocator<void >>;
84+ using MyMessage = MyAllocMessage<MyAllocator<void >>;
85+
86+ static_assert (!tf2::impl::MessageHasStdHeader<MyVec>::value, " MessageHasStdHeader traits error" );
87+ static_assert (
88+ tf2::impl::MessageHasStdHeader<MyVecStamped>::value,
89+ " MessageHasStdHeader traits error" );
90+
91+ static_assert (
92+ !tf2::impl::MessageHasStdHeader<MyMessage>::value,
93+ " MessageHasStdHeader traits error" );
94+ } // namespace
95+
4496using Vector6d = Eigen::Matrix<double , 6 , 1 >;
4597
4698TEST (tf2Convert, kdlToBullet)
@@ -245,7 +297,6 @@ TEST(TfEigenKdl, TestTwistMatrix)
245297 EXPECT_EQ (kdl_v, kdl_v1);
246298}
247299
248-
249300TEST (TfEigenKdl, TestMatrixWrench)
250301{
251302 Vector6d eigen_v;
@@ -263,7 +314,6 @@ TEST(TfEigenKdl, TestMatrixWrench)
263314 EXPECT_EQ (eigen_v, eigen_v2);
264315}
265316
266-
267317TEST (TfEigenKdl, TestVectorVector3d)
268318{
269319 const auto kdl_v = KDL::Vector (1 , 2 , 3 );
0 commit comments