test_tf_projection.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014-2017, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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       // projected: t(1.0, 3.0, 0.0), r((0.0, 0.0, 1.0), M_PI/2.0)
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       // rotate 90deg: (-3.0, 1.0, 0.0), r((0.0, 0.0, 1.0), M_PI)
00069       // offset x+1.0, z+0.5: t(-2.0, 1.0, 0.5), r((0.0, 0.0, 1.0), M_PI)
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       // projected: t(1.0, 1.0, 0.0), r((0.0, 0.0, 1.0), 0.0)
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       // rotate 30deg and offset to make it on z axis
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 }


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:23