30 #include <gtest/gtest.h>
39 geometry_msgs::TransformStamped st;
47 geometry_msgs::TransformStamped st;
48 st.header.frame_id =
"foo";
50 st.child_frame_id =
"child";
51 st.transform.rotation.w = 1;
59 geometry_msgs::TransformStamped st;
60 st.header.frame_id =
"foo";
62 st.child_frame_id =
"child";
63 st.transform.rotation.w = 0;
68 TEST(tf2_lookupTransform, LookupException_Nothing_Exists)
75 TEST(tf2_canTransform, Nothing_Exists)
80 std::string error_msg = std::string();
82 ASSERT_STREQ(error_msg.c_str(),
"canTransform: target_frame a does not exist. canTransform: source_frame b does not exist.");
86 TEST(tf2_lookupTransform, LookupException_One_Exists)
89 geometry_msgs::TransformStamped st;
90 st.header.frame_id =
"foo";
92 st.child_frame_id =
"child";
93 st.transform.rotation.w = 1;
99 TEST(tf2_canTransform, One_Exists)
102 geometry_msgs::TransformStamped st;
103 st.header.frame_id =
"foo";
105 st.child_frame_id =
"child";
106 st.transform.rotation.w = 1;
111 TEST(tf2_chainAsVector, chain_v_configuration)
116 geometry_msgs::TransformStamped st;
118 st.transform.rotation.w = 1;
120 st.header.frame_id =
"a";
121 st.child_frame_id =
"b";
124 st.header.frame_id =
"b";
125 st.child_frame_id =
"c";
128 st.header.frame_id =
"a";
129 st.child_frame_id =
"d";
132 st.header.frame_id =
"d";
133 st.child_frame_id =
"e";
136 std::vector<std::string> chain;
140 EXPECT_EQ( 0, chain.size());
143 EXPECT_EQ( 3, chain.size());
144 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"c" );
145 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
146 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
149 EXPECT_EQ( 3, chain.size());
150 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"a" );
151 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
152 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"c" );
155 EXPECT_EQ( 3, chain.size());
156 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"c" );
157 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
158 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
161 EXPECT_EQ( 3, chain.size());
162 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"a" );
163 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
164 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"c" );
168 EXPECT_EQ( 5, chain.size());
169 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
170 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
171 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
172 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
173 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
177 EXPECT_EQ( 5, chain.size());
178 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
179 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
180 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
181 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
182 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
186 EXPECT_EQ( 5, chain.size());
187 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
188 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
189 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
190 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
191 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
194 TEST(tf2_walkToTopParent, walk_i_configuration)
199 geometry_msgs::TransformStamped st;
201 st.transform.rotation.w = 1;
203 st.header.frame_id =
"a";
204 st.child_frame_id =
"b";
207 st.header.frame_id =
"b";
208 st.child_frame_id =
"c";
211 st.header.frame_id =
"c";
212 st.child_frame_id =
"d";
215 st.header.frame_id =
"d";
216 st.child_frame_id =
"e";
219 std::vector<tf2::CompactFrameID> id_chain;
222 EXPECT_EQ(5, id_chain.size() );
232 EXPECT_EQ(5, id_chain.size() );
241 TEST(tf2_walkToTopParent, walk_v_configuration)
246 geometry_msgs::TransformStamped st;
248 st.transform.rotation.w = 1;
258 st.header.frame_id =
"a";
259 st.child_frame_id =
"b";
262 st.header.frame_id =
"b";
263 st.child_frame_id =
"c";
266 st.header.frame_id =
"a";
267 st.child_frame_id =
"d";
270 st.header.frame_id =
"d";
271 st.child_frame_id =
"e";
274 std::vector<tf2::CompactFrameID> id_chain;
277 EXPECT_EQ(5, id_chain.size());
285 EXPECT_EQ(5, id_chain.size());
293 EXPECT_EQ( id_chain.size(), 3 );
299 EXPECT_EQ( id_chain.size(), 3 );
305 EXPECT_EQ( id_chain.size(), 2 );
310 EXPECT_EQ( id_chain.size(), 2 );
316 int main(
int argc,
char **argv){
317 testing::InitGoogleTest(&argc, argv);
319 return RUN_ALL_TESTS();