test_tf_projection_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <cmath>
31 #include <string>
32 
33 #include <ros/ros.h>
34 #include <geometry_msgs/TransformStamped.h>
35 #include <tf2/utils.h>
36 #include <tf2_ros/buffer.h>
38 
39 #include <gtest/gtest.h>
40 
41 class TfProjectionTest : public ::testing::TestWithParam<const char*>
42 {
43 public:
46 
47  std::string projected_frame_;
48 
50  : tfl_(tfbuf_)
51  {
52  }
53  void SetUp() override
54  {
55  projected_frame_ = std::string(GetParam());
56  }
57 };
58 
59 TEST_P(TfProjectionTest, ProjectionTransform)
60 {
61  EXPECT_TRUE(tfbuf_.canTransform("map", projected_frame_, ros::Time(0), ros::Duration(10.0)));
62 
63  geometry_msgs::TransformStamped out;
64  try
65  {
67  }
68  catch (tf2::TransformException& e)
69  {
70  FAIL() << e.what();
71  }
72 
73  if (projected_frame_ == "base_link_tilt_projected_with_aligned")
74  {
75  const tf2::Transform trans(
76  tf2::Quaternion(tf2::Vector3(0.0, 1.0, 0.0), -M_PI / 6));
77  const tf2::Vector3 result = trans * tf2::Vector3(1, 2, 3);
78  ASSERT_NEAR(out.transform.translation.x, result[0], 1e-4);
79  }
80  else
81  {
82  ASSERT_NEAR(out.transform.translation.x, 1, 1e-4);
83  }
84  ASSERT_NEAR(out.transform.translation.y, 2, 1e-4);
85  ASSERT_NEAR(out.transform.translation.z, 0, 1e-4);
86  ASSERT_NEAR(out.transform.rotation.x, 0, 1e-4);
87  ASSERT_NEAR(out.transform.rotation.y, 0, 1e-4);
88  ASSERT_NEAR(out.transform.rotation.z, 0.7071, 1e-4);
89  ASSERT_NEAR(out.transform.rotation.w, 0.7071, 1e-4);
90  ASSERT_EQ(out.header.frame_id, "map");
91  ASSERT_EQ(out.child_frame_id, projected_frame_);
92 }
93 
95  ProjectionTransformInstance, TfProjectionTest,
96  ::testing::Values(
97  "base_link_projected",
98  "base_link_projected2",
99  "base_link_tilt_projected",
100  "base_link_tilt_projected_with_aligned"));
101 
102 int main(int argc, char** argv)
103 {
104  testing::InitGoogleTest(&argc, argv);
105  ros::init(argc, argv, "test_tf_projection_node");
106 
107  return RUN_ALL_TESTS();
108 }
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
tf2_ros::TransformListener tfl_
INSTANTIATE_TEST_CASE_P(ProjectionTransformInstance, TfProjectionTest,::testing::Values("base_link_projected","base_link_projected2","base_link_tilt_projected","base_link_tilt_projected_with_aligned"))
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
int main(int argc, char **argv)
TEST_P(TfProjectionTest, ProjectionTransform)


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:38