test_frames_and_slashes.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, Open Source Robotics Foundation, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 
36 #include <string>
37 #include <vector>
38 
39 #include <gtest/gtest.h>
40 #include <ros/ros.h>
41 #include <geometry_msgs/Transform.h>
42 #include <tf2_msgs/TFMessage.h>
43 
44 #define EPS 0.01
45 
46 class TestFramesAndSlashes : public testing::Test
47 {
48 protected:
50  {
52  "/tf_static", 1, &TestFramesAndSlashes::tf_static_callback, this);
53  }
54 
55  ~TestFramesAndSlashes() = default;
56 
57  void
58  tf_static_callback(const tf2_msgs::TFMessage::ConstPtr msg)
59  {
60  transforms_received_ = *msg;
61  // avoid writing another message while test is reading the one received
63  got_transforms_ = true;
64  }
65 
69  tf2_msgs::TFMessage transforms_received_;
70  bool got_transforms_ = false;
71 };
72 
74 {
75  std::vector<std::string> expected_links(13);
76 
77  {
78  ros::NodeHandle n_tilde;
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]));
94  }
95 
96  for (int i = 0; i < 100 && !got_transforms_; ++i) {
97  ros::Duration(0.1).sleep();
98  ros::spinOnce();
99  }
100  ASSERT_TRUE(got_transforms_);
101 
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);
105 
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)
111  {
112  transform = tf_stamped.transform;
113  found_transform_ = true;
114  }
115  }
116 
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;
120  }
121  }
122 
123  // Print transforms received for easier debugging
124  EXPECT_FALSE(testing::Test::HasFailure()) << transforms_received_;
125 }
126 
127 int main(int argc, char** argv)
128 {
129  testing::InitGoogleTest(&argc, argv);
130  ros::init(argc, argv, "test_frames_and_slashes");
131 
132  int res = RUN_ALL_TESTS();
133 
134  return res;
135 }
main
int main(int argc, char **argv)
Definition: test_frames_and_slashes.cpp:127
TEST_F
TEST_F(TestFramesAndSlashes, test)
Definition: test_frames_and_slashes.cpp:73
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TestFramesAndSlashes
Definition: test_frames_and_slashes.cpp:46
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
TestFramesAndSlashes::tf_static_sub_
ros::Subscriber tf_static_sub_
Definition: test_frames_and_slashes.cpp:68
ros::Subscriber::shutdown
void shutdown()
TestFramesAndSlashes::transforms_received_
tf2_msgs::TFMessage transforms_received_
Definition: test_frames_and_slashes.cpp:69
test
TestFramesAndSlashes::got_transforms_
bool got_transforms_
Definition: test_frames_and_slashes.cpp:70
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
TestFramesAndSlashes::TestFramesAndSlashes
TestFramesAndSlashes()
Definition: test_frames_and_slashes.cpp:49
EPS
#define EPS
Definition: test_frames_and_slashes.cpp:44
TestFramesAndSlashes::tf_sub_
ros::Subscriber tf_sub_
Definition: test_frames_and_slashes.cpp:67
TestFramesAndSlashes::~TestFramesAndSlashes
~TestFramesAndSlashes()=default
ros::Duration::sleep
bool sleep() const
ros::Duration
TestFramesAndSlashes::tf_static_callback
void tf_static_callback(const tf2_msgs::TFMessage::ConstPtr msg)
Definition: test_frames_and_slashes.cpp:58
ros::NodeHandle
ros::Subscriber
TestFramesAndSlashes::n_
ros::NodeHandle n_
Definition: test_frames_and_slashes.cpp:66


robot_state_publisher
Author(s): Ioan Sucan , Jackie Kay , Wim Meeussen
autogenerated on Mon Aug 12 2024 02:09:28