Skip to content

Commit

Permalink
verbose message testing
Browse files Browse the repository at this point in the history
  • Loading branch information
gleichdick committed May 26, 2021
1 parent f727fdb commit c09c38f
Showing 1 changed file with 52 additions and 2 deletions.
54 changes: 52 additions & 2 deletions test_tf2/test/test_convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,65 @@
*
* Author: Eitan Marder-Eppstein
*********************************************************************/

#include <geometry_msgs/msg/vector3_stamped.hpp>
#include <gtest/gtest.h>
#include <tf2/convert.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_bullet/tf2_bullet.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_kdl/tf2_kdl.hpp>


// test of tf2 type traits
static_assert(
!tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3>::value,
"MessageHasStdHeader traits error");
static_assert(
tf2::impl::MessageHasStdHeader<geometry_msgs::msg::Vector3Stamped>::value,
"MessageHasStdHeader traits error");

namespace
{
struct MyPODMessage
{
int header;
};

template<typename Alloc>
struct MyAllocMessage
{
int header;
};

static_assert(
!tf2::impl::MessageHasStdHeader<MyPODMessage>::value,
"MessageHasStdHeader traits error");

template<typename T>
struct MyAllocator
{
using value_type = T;
using size_type = unsigned int;
T * allocate(size_type);
void deallocate(T *, size_type);
template<class U>
struct rebind { typedef MyAllocator<U> other; };
};
using MyVec = geometry_msgs::msg::Vector3_<MyAllocator<void>>;
using MyVecStamped = geometry_msgs::msg::Vector3Stamped_<MyAllocator<void>>;
using MyMessage = MyAllocMessage<MyAllocator<void>>;

static_assert(!tf2::impl::MessageHasStdHeader<MyVec>::value, "MessageHasStdHeader traits error");
static_assert(
tf2::impl::MessageHasStdHeader<MyVecStamped>::value,
"MessageHasStdHeader traits error");

static_assert(
!tf2::impl::MessageHasStdHeader<MyMessage>::value,
"MessageHasStdHeader traits error");
} // namespace

using Vector6d = Eigen::Matrix<double, 6, 1>;

TEST(tf2Convert, kdlToBullet)
Expand Down Expand Up @@ -245,7 +297,6 @@ TEST(TfEigenKdl, TestTwistMatrix)
EXPECT_EQ(kdl_v, kdl_v1);
}


TEST(TfEigenKdl, TestMatrixWrench)
{
Vector6d eigen_v;
Expand All @@ -263,7 +314,6 @@ TEST(TfEigenKdl, TestMatrixWrench)
EXPECT_EQ(eigen_v, eigen_v2);
}


TEST(TfEigenKdl, TestVectorVector3d)
{
const auto kdl_v = KDL::Vector(1, 2, 3);
Expand Down

0 comments on commit c09c38f

Please sign in to comment.