30 #include <gtest/gtest.h> 40 geometry_msgs::TransformStamped st;
48 geometry_msgs::TransformStamped st;
49 st.header.frame_id =
"foo";
51 st.child_frame_id =
"child";
52 st.transform.rotation.w = 1;
60 geometry_msgs::TransformStamped st;
61 st.header.frame_id =
"foo";
63 st.child_frame_id =
"child";
64 st.transform.rotation.w = 0;
69 TEST(tf2_lookupTransform, LookupException_Nothing_Exists)
76 TEST(tf2_canTransform, Nothing_Exists)
81 std::string error_msg = std::string();
83 ASSERT_STREQ(error_msg.c_str(),
"canTransform: target_frame a does not exist. canTransform: source_frame b does not exist.");
87 TEST(tf2_lookupTransform, LookupException_One_Exists)
90 geometry_msgs::TransformStamped st;
91 st.header.frame_id =
"foo";
93 st.child_frame_id =
"child";
94 st.transform.rotation.w = 1;
100 TEST(tf2_canTransform, One_Exists)
103 geometry_msgs::TransformStamped st;
104 st.header.frame_id =
"foo";
106 st.child_frame_id =
"child";
107 st.transform.rotation.w = 1;
112 TEST(tf2_chainAsVector, chain_v_configuration)
117 geometry_msgs::TransformStamped st;
119 st.transform.rotation.w = 1;
121 st.header.frame_id =
"a";
122 st.child_frame_id =
"b";
125 st.header.frame_id =
"b";
126 st.child_frame_id =
"c";
129 st.header.frame_id =
"a";
130 st.child_frame_id =
"d";
133 st.header.frame_id =
"d";
134 st.child_frame_id =
"e";
137 std::vector<std::string> chain;
141 EXPECT_EQ( 0, chain.size());
144 EXPECT_EQ( 3, chain.size());
145 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"c" );
146 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
147 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
150 EXPECT_EQ( 3, chain.size());
151 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"a" );
152 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
153 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"c" );
156 EXPECT_EQ( 3, chain.size());
157 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"c" );
158 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
159 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
162 EXPECT_EQ( 3, chain.size());
163 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"a" );
164 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"b" );
165 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"c" );
169 EXPECT_EQ( 5, chain.size());
170 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
171 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
172 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
173 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
174 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
178 EXPECT_EQ( 5, chain.size());
179 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
180 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
181 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
182 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
183 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
187 EXPECT_EQ( 5, chain.size());
188 if( chain.size() >= 1 ) EXPECT_EQ( chain[0],
"e" );
189 if( chain.size() >= 2 ) EXPECT_EQ( chain[1],
"d" );
190 if( chain.size() >= 3 ) EXPECT_EQ( chain[2],
"a" );
191 if( chain.size() >= 4 ) EXPECT_EQ( chain[3],
"b" );
192 if( chain.size() >= 5 ) EXPECT_EQ( chain[4],
"c" );
195 TEST(tf2_walkToTopParent, walk_i_configuration)
200 geometry_msgs::TransformStamped st;
202 st.transform.rotation.w = 1;
204 st.header.frame_id =
"a";
205 st.child_frame_id =
"b";
208 st.header.frame_id =
"b";
209 st.child_frame_id =
"c";
212 st.header.frame_id =
"c";
213 st.child_frame_id =
"d";
216 st.header.frame_id =
"d";
217 st.child_frame_id =
"e";
220 std::vector<tf2::CompactFrameID> id_chain;
223 EXPECT_EQ(5, id_chain.size() );
233 EXPECT_EQ(5, id_chain.size() );
242 TEST(tf2_walkToTopParent, walk_v_configuration)
247 geometry_msgs::TransformStamped st;
249 st.transform.rotation.w = 1;
259 st.header.frame_id =
"a";
260 st.child_frame_id =
"b";
263 st.header.frame_id =
"b";
264 st.child_frame_id =
"c";
267 st.header.frame_id =
"a";
268 st.child_frame_id =
"d";
271 st.header.frame_id =
"d";
272 st.child_frame_id =
"e";
275 std::vector<tf2::CompactFrameID> id_chain;
278 EXPECT_EQ(5, id_chain.size());
286 EXPECT_EQ(5, id_chain.size());
294 EXPECT_EQ( id_chain.size(), 3 );
300 EXPECT_EQ( id_chain.size(), 3 );
306 EXPECT_EQ( id_chain.size(), 2 );
311 EXPECT_EQ( id_chain.size(), 2 );
317 int main(
int argc,
char **argv){
318 testing::InitGoogleTest(&argc, argv);
320 return RUN_ALL_TESTS();
TEST(tf2, setTransformFail)
A Class which provides coordinate transforms between any two frames in a system.
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
Add transform information to the tf data structure.
const std::string & _lookupFrameString(BufferCore &buffer, CompactFrameID frame_id_num) const
An exception class to notify of bad frame number.
void _chainAsVector(const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
Backwards compatabilityA way to see what frames are in a chain Useful for debugging.
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if a transform is possible.
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
int main(int argc, char **argv)
int _walkToTopParent(BufferCore &buffer, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string, std::vector< CompactFrameID > *frame_chain) const
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
Get the transform between two frames by frame ID.