Skip to content

Commit b8b291f

Browse files
committed
Unit test for doTransform(QuaternionStamped)
1 parent 7fb4715 commit b8b291f

File tree

1 file changed

+33
-0
lines changed

1 file changed

+33
-0
lines changed

tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -230,6 +230,39 @@ TEST(TfGeometry, Point)
230230
EXPECT_NEAR(v_advanced.point.z, 27, EPS);
231231
}
232232

233+
TEST(TfGeometry, Quaternion)
234+
{
235+
// rotated by -90° around y
236+
// 0, 0, -1
237+
// 0, 1, 0,
238+
// 1, 0, 0
239+
geometry_msgs::msg::QuaternionStamped q1, res;
240+
q1.quaternion.x = 0;
241+
q1.quaternion.y = -1 * M_SQRT1_2;
242+
q1.quaternion.z = 0;
243+
q1.quaternion.w = M_SQRT1_2;
244+
q1.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(2));
245+
q1.header.frame_id = "A";
246+
247+
// simple api
248+
const geometry_msgs::msg::QuaternionStamped q_simple = tf_buffer->transform(
249+
q1, "B", tf2::durationFromSec(
250+
2.0));
251+
EXPECT_NEAR(q_simple.quaternion.x, M_SQRT1_2, EPS);
252+
EXPECT_NEAR(q_simple.quaternion.y, 0, EPS);
253+
EXPECT_NEAR(q_simple.quaternion.z, -1 * M_SQRT1_2, EPS);
254+
EXPECT_NEAR(q_simple.quaternion.w, 0, EPS);
255+
256+
// advanced api
257+
const geometry_msgs::msg::QuaternionStamped q_advanced = tf_buffer->transform(
258+
q1, "B", tf2::timeFromSec(2.0),
259+
"A", tf2::durationFromSec(3.0));
260+
EXPECT_NEAR(q_advanced.quaternion.x, M_SQRT1_2, EPS);
261+
EXPECT_NEAR(q_advanced.quaternion.y, 0, EPS);
262+
EXPECT_NEAR(q_advanced.quaternion.z, -1 * M_SQRT1_2, EPS);
263+
EXPECT_NEAR(q_advanced.quaternion.w, 0, EPS);
264+
}
265+
233266

234267
int main(int argc, char **argv){
235268
testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)