00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031 #include <tf2/LinearMath/Transform.h>
00032 #include <tf2/transform_datatypes.h>
00033
00034 #include <track_odometry/tf_projection.h>
00035 #include <gtest/gtest.h>
00036
00037 void testTransform(
00038 const tf2::Stamped<tf2::Transform> proj2base,
00039 const tf2::Stamped<tf2::Transform> targ2proj,
00040 const tf2::Stamped<tf2::Transform> truth)
00041 {
00042 tf2::Transform result = track_odometry::projectTranslation(proj2base, targ2proj);
00043
00044 const float error_x = fabs(result.getOrigin().x() - truth.getOrigin().x());
00045 const float error_y = fabs(result.getOrigin().y() - truth.getOrigin().y());
00046 const float error_z = fabs(result.getOrigin().z() - truth.getOrigin().z());
00047 const tf2::Quaternion error_q = result.getRotation() * truth.getRotation().inverse();
00048 ASSERT_LT(error_x, 0.001);
00049 ASSERT_LT(error_y, 0.001);
00050 ASSERT_LT(error_z, 0.001);
00051 ASSERT_LT(fabs(error_q.getAngle()), 0.001);
00052 }
00053
00054 TEST(TfProjection, ProjectionTransform)
00055 {
00056 testTransform(
00057 tf2::Stamped<tf2::Transform>(
00058 tf2::Transform(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), M_PI / 2.0),
00059 tf2::Vector3(1.0, 3.0, 10.0)),
00060 ros::Time(0),
00061 "map"),
00062
00063 tf2::Stamped<tf2::Transform>(
00064 tf2::Transform(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), M_PI / 2.0),
00065 tf2::Vector3(1.0, 0.0, 0.5)),
00066 ros::Time(0),
00067 "odom"),
00068
00069
00070 tf2::Stamped<tf2::Transform>(
00071 tf2::Transform(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), M_PI),
00072 tf2::Vector3(-2.0, 1.0, 0.5)),
00073 ros::Time(0),
00074 "odom"));
00075
00076 testTransform(
00077 tf2::Stamped<tf2::Transform>(
00078 tf2::Transform(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), 0.0),
00079 tf2::Vector3(1.0, 1.0, 100.0)),
00080 ros::Time(0),
00081 "map"),
00082
00083 tf2::Stamped<tf2::Transform>(
00084 tf2::Transform(tf2::Quaternion(tf2::Vector3(1.0, 0.0, 0.0), M_PI / 6.0),
00085 tf2::Vector3(0.0, -sqrtf(3.0) / 2.0, 3.0 / 2.0)),
00086 ros::Time(0),
00087 "odom"),
00088
00089 tf2::Stamped<tf2::Transform>(
00090 tf2::Transform(tf2::Quaternion(tf2::Vector3(1.0, 0.0, 0.0), M_PI / 6.0),
00091 tf2::Vector3(1.0, 0.0, 2.0)),
00092 ros::Time(0),
00093 "odom"));
00094 }
00095
00096 int main(int argc, char** argv)
00097 {
00098 ::testing::InitGoogleTest(&argc, argv);
00099
00100 return RUN_ALL_TESTS();
00101 }