Skip to content

Commit 930705b

Browse files
committed
Add Eigen buffer transform tests
1 parent d19ce64 commit 930705b

File tree

1 file changed

+155
-3
lines changed

1 file changed

+155
-3
lines changed

tf2_eigen/test/tf2_eigen-test.cpp

Lines changed: 155 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,18 +26,26 @@
2626

2727
/** \author Wim Meeussen */
2828

29+
// To get M_PI, especially on Windows.
30+
2931
#ifdef _MSC_VER
3032
#ifndef _USE_MATH_DEFINES
3133
#define _USE_MATH_DEFINES
3234
#endif
3335
#endif
3436

35-
// To get M_PI, especially on Windows.
3637
#include <math.h>
3738

38-
#include <tf2_eigen/tf2_eigen.h>
39+
3940
#include <gtest/gtest.h>
4041
#include <tf2/convert.h>
42+
#include <tf2_eigen/tf2_eigen.h>
43+
#include <tf2_ros/buffer.h>
44+
#include <tf2_ros/transform_listener.h>
45+
46+
47+
#include <memory>
48+
#include <rclcpp/clock.hpp>
4149

4250
// TODO(clalancette) Re-enable these tests once we have tf2/convert.h:convert(A, B) implemented
4351
// TEST(TfEigen, ConvertVector3dStamped)
@@ -124,7 +132,151 @@ TEST(TfEigen, ConvertTransform)
124132
EXPECT_TRUE(tm.isApprox(Iback.matrix()));
125133
}
126134

127-
int main(int argc, char **argv){
135+
struct EigenBufferTransform : public ::testing::Test
136+
{
137+
static void SetUpTestSuite()
138+
{
139+
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
140+
tf_buffer = std::make_unique<tf2_ros::Buffer>(clock);
141+
tf_buffer->setUsingDedicatedThread(true);
142+
143+
// populate buffer
144+
geometry_msgs::msg::TransformStamped t;
145+
t.transform.translation.x = 10;
146+
t.transform.translation.y = 20;
147+
t.transform.translation.z = 30;
148+
t.transform.rotation.w = 0;
149+
t.transform.rotation.x = 1;
150+
t.transform.rotation.y = 0;
151+
t.transform.rotation.z = 0;
152+
t.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(2));
153+
t.header.frame_id = "A";
154+
t.child_frame_id = "B";
155+
tf_buffer->setTransform(t, "test");
156+
}
157+
158+
template<int mode>
159+
void testEigenTransform();
160+
161+
::testing::AssertionResult doTestEigenQuaternion(
162+
const Eigen::Quaterniond & parameter, const Eigen::Quaterniond & expected);
163+
164+
static std::unique_ptr<tf2_ros::Buffer> tf_buffer;
165+
static constexpr double EPS = 1e-3;
166+
};
167+
168+
std::unique_ptr<tf2_ros::Buffer> EigenBufferTransform::tf_buffer;
169+
170+
template<int mode>
171+
void EigenBufferTransform::testEigenTransform()
172+
{
173+
using T = Eigen::Transform<double, 3, mode>;
174+
using stampedT = tf2::Stamped<T>;
175+
176+
const stampedT i1{
177+
T{Eigen::Translation3d{1, 2, 3} *Eigen::Quaterniond{0, 1, 0, 0}}, tf2::timeFromSec(2), "A"};
178+
179+
// simple api
180+
const stampedT i_simple = tf_buffer->transform(i1, "B", tf2::durationFromSec(2.0));
181+
EXPECT_NEAR(i_simple.translation().x(), -9, EPS);
182+
EXPECT_NEAR(i_simple.translation().y(), 18, EPS);
183+
EXPECT_NEAR(i_simple.translation().z(), 27, EPS);
184+
const auto q1 = Eigen::Quaterniond(i_simple.linear());
185+
EXPECT_NEAR(q1.x(), 0.0, EPS);
186+
EXPECT_NEAR(q1.y(), 0.0, EPS);
187+
EXPECT_NEAR(q1.z(), 0.0, EPS);
188+
EXPECT_NEAR(q1.w(), 1.0, EPS);
189+
190+
// advanced api
191+
const stampedT v_advanced =
192+
tf_buffer->transform(i1, "B", tf2::timeFromSec(2.0), "A", tf2::durationFromSec(3.0));
193+
EXPECT_NEAR(v_advanced.translation().x(), -9, EPS);
194+
EXPECT_NEAR(v_advanced.translation().y(), 18, EPS);
195+
EXPECT_NEAR(v_advanced.translation().z(), 27, EPS);
196+
const auto q2 = Eigen::Quaterniond(v_advanced.linear());
197+
EXPECT_NEAR(q2.x(), 0.0, EPS);
198+
EXPECT_NEAR(q2.y(), 0.0, EPS);
199+
EXPECT_NEAR(q2.z(), 0.0, EPS);
200+
EXPECT_NEAR(q2.w(), 1.0, EPS);
201+
}
202+
203+
TEST_F(EigenBufferTransform, Affine3d) {
204+
testEigenTransform<Eigen::Affine>();
205+
}
206+
207+
TEST_F(EigenBufferTransform, Isometry3d) {
208+
testEigenTransform<Eigen::Isometry>();
209+
}
210+
211+
TEST_F(EigenBufferTransform, Vector)
212+
{
213+
const tf2::Stamped<Eigen::Vector3d> v1{{1, 2, 3}, tf2::timeFromSec(2), "A"};
214+
215+
// simple api
216+
const tf2::Stamped<Eigen::Vector3d> v_simple =
217+
tf_buffer->transform(v1, "B", tf2::durationFromSec(2.0));
218+
EXPECT_NEAR(v_simple.x(), -9, EPS);
219+
EXPECT_NEAR(v_simple.y(), 18, EPS);
220+
EXPECT_NEAR(v_simple.z(), 27, EPS);
221+
222+
// advanced api
223+
const tf2::Stamped<Eigen::Vector3d> v_advanced =
224+
tf_buffer->transform(v1, "B", tf2::timeFromSec(2.0), "A", tf2::durationFromSec(3.0));
225+
EXPECT_NEAR(v_advanced.x(), -9, EPS);
226+
EXPECT_NEAR(v_advanced.y(), 18, EPS);
227+
EXPECT_NEAR(v_advanced.z(), 27, EPS);
228+
}
229+
230+
// helper method for Quaternion tests
231+
::testing::AssertionResult EigenBufferTransform::doTestEigenQuaternion(
232+
const Eigen::Quaterniond & parameter, const Eigen::Quaterniond & expected)
233+
{
234+
const tf2::Stamped<Eigen::Quaterniond> q1{parameter, tf2::timeFromSec(2), "A"};
235+
// avoid linking error
236+
const double eps = EPS;
237+
238+
// simple api
239+
const tf2::Stamped<Eigen::Quaterniond> q_simple =
240+
tf_buffer->transform(q1, "B", tf2::durationFromSec(2.0));
241+
// compare rotation matrices, as the quaternions can be ambigous
242+
EXPECT_TRUE(q_simple.toRotationMatrix().isApprox(expected.toRotationMatrix(), eps));
243+
244+
// advanced api
245+
const tf2::Stamped<Eigen::Quaterniond> q_advanced =
246+
tf_buffer->transform(q1, "B", tf2::timeFromSec(2.0), "A", tf2::durationFromSec(3.0));
247+
EXPECT_TRUE(q_advanced.toRotationMatrix().isApprox(expected.toRotationMatrix(), eps));
248+
return ::testing::AssertionSuccess();
249+
}
250+
251+
TEST_F(EigenBufferTransform, QuaternionRotY)
252+
{
253+
// rotated by -90° around y
254+
// 0, 0, -1
255+
// 0, 1, 0,
256+
// 1, 0, 0
257+
const Eigen::Quaterniond param{Eigen::AngleAxisd(-1 * M_PI_2, Eigen::Vector3d::UnitY())};
258+
const Eigen::Quaterniond expected{0, M_SQRT1_2, 0, -1 * M_SQRT1_2};
259+
EXPECT_TRUE(doTestEigenQuaternion(param, expected));
260+
}
261+
262+
TEST_F(EigenBufferTransform, QuaternionRotX)
263+
{
264+
// rotated by 90° around y
265+
const Eigen::Quaterniond param{Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitX())};
266+
const Eigen::Quaterniond expected{Eigen::AngleAxisd(-1 * M_PI_2, Eigen::Vector3d::UnitX())};
267+
EXPECT_TRUE(doTestEigenQuaternion(param, expected));
268+
}
269+
270+
TEST_F(EigenBufferTransform, QuaternionRotZ)
271+
{
272+
// rotated by 180° around z
273+
const Eigen::Quaterniond param{Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitZ())};
274+
const Eigen::Quaterniond expected{Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitY())};
275+
EXPECT_TRUE(doTestEigenQuaternion(param, expected));
276+
}
277+
278+
int main(int argc, char ** argv)
279+
{
128280
testing::InitGoogleTest(&argc, argv);
129281

130282
return RUN_ALL_TESTS();

0 commit comments

Comments
 (0)