39 #include <gtest/gtest.h>
41 #include <geometry_msgs/Transform.h>
42 #include <tf2_msgs/TFMessage.h>
75 std::vector<std::string> expected_links(13);
79 std::string robot_description;
80 ASSERT_TRUE(n_tilde.
getParam(
"robot_description", robot_description));
81 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_1", expected_links[0]));
82 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_2", expected_links[1]));
83 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_3", expected_links[2]));
84 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_4", expected_links[3]));
85 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_5", expected_links[4]));
86 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_6", expected_links[5]));
87 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_7", expected_links[6]));
88 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_8", expected_links[7]));
89 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_9", expected_links[8]));
90 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_10", expected_links[9]));
91 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_11", expected_links[10]));
92 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_12", expected_links[11]));
93 ASSERT_TRUE(n_tilde.
getParam(
"expected_name_link_13", expected_links[12]));
96 for (
int i = 0; i < 100 && !got_transforms_; ++i) {
100 ASSERT_TRUE(got_transforms_);
102 for (
size_t n = 1; n < expected_links.size(); ++n) {
103 const std::string & link_1 = expected_links.at(0);
104 const std::string & link_n = expected_links.at(n);
106 bool found_transform_ =
false;
107 geometry_msgs::Transform transform;
108 for (
const geometry_msgs::TransformStamped & tf_stamped : transforms_received_.transforms) {
109 if (tf_stamped.header.frame_id == link_1 &&
110 tf_stamped.child_frame_id == link_n)
112 transform = tf_stamped.transform;
113 found_transform_ =
true;
117 EXPECT_TRUE(found_transform_) <<
"expected " << link_1 <<
" and " << link_n;
118 if (found_transform_) {
119 EXPECT_NEAR(transform.translation.x, n + 1,
EPS) <<
"frames " << link_1 <<
" and " << link_n;
124 EXPECT_FALSE(testing::Test::HasFailure()) << transforms_received_;
127 int main(
int argc,
char** argv)
129 testing::InitGoogleTest(&argc, argv);
130 ros::init(argc, argv,
"test_frames_and_slashes");
132 int res = RUN_ALL_TESTS();