test_quat.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2016-2017, the mcl_3dl 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 #define _USE_MATH_DEFINES
00031 
00032 #include <cstddef>
00033 #include <cmath>
00034 
00035 #include <gtest/gtest.h>
00036 
00037 #include <mcl_3dl/quat.h>
00038 
00039 TEST(Quat, Constractors)
00040 {
00041   // Test quaternion elements style constructor and copy constructor
00042   const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
00043   const mcl_3dl::Quat b(a);
00044 
00045   ASSERT_TRUE(a.x_ == 1.0);
00046   ASSERT_TRUE(a.y_ == 2.0);
00047   ASSERT_TRUE(a.z_ == 3.0);
00048   ASSERT_TRUE(a.w_ == 4.0);
00049   ASSERT_TRUE(b.x_ == 1.0);
00050   ASSERT_TRUE(b.y_ == 2.0);
00051   ASSERT_TRUE(b.z_ == 3.0);
00052   ASSERT_TRUE(b.w_ == 4.0);
00053 
00054   // Test RPY and angle-axis style constructor
00055   for (int i = 0; i < 3; ++i)
00056   {
00057     const float ang = M_PI / 2.0;
00058     const float r = (i == 0) ? 1.0 : 0.0;
00059     const float p = (i == 1) ? 1.0 : 0.0;
00060     const float y = (i == 2) ? 1.0 : 0.0;
00061 
00062     // Check consistency between styles
00063     const mcl_3dl::Quat c(mcl_3dl::Vec3(r * ang, p * ang, y * ang));
00064     mcl_3dl::Quat d;
00065     d.setRPY(mcl_3dl::Vec3(r * ang, p * ang, y * ang));
00066     ASSERT_TRUE(c == d);
00067 
00068     const mcl_3dl::Quat e(mcl_3dl::Vec3(r, p, y), ang);
00069     ASSERT_LT(fabs(c.x_ - e.x_), 1e-6);
00070     ASSERT_LT(fabs(c.y_ - e.y_), 1e-6);
00071     ASSERT_LT(fabs(c.z_ - e.z_), 1e-6);
00072     ASSERT_LT(fabs(c.w_ - e.w_), 1e-6);
00073 
00074     // Check elements
00075     ASSERT_LT(fabs(c.x_ - r * sqrtf(2.0) / 2.0), 1e-6);
00076     ASSERT_LT(fabs(c.y_ - p * sqrtf(2.0) / 2.0), 1e-6);
00077     ASSERT_LT(fabs(c.z_ - y * sqrtf(2.0) / 2.0), 1e-6);
00078     ASSERT_LT(fabs(c.w_ - sqrtf(2.0) / 2.0), 1e-6);
00079 
00080     // Check reverse conversions
00081     mcl_3dl::Vec3 crpy(c.getRPY());
00082     ASSERT_LT(fabs(r * ang - crpy.x_), 1e-3);
00083     ASSERT_LT(fabs(p * ang - crpy.y_), 1e-3);
00084     ASSERT_LT(fabs(y * ang - crpy.z_), 1e-3);
00085 
00086     mcl_3dl::Vec3 axis;
00087     float angle;
00088     c.getAxisAng(axis, angle);
00089     ASSERT_LT(fabs(r - axis.x_), 1e-6);
00090     ASSERT_LT(fabs(p - axis.y_), 1e-6);
00091     ASSERT_LT(fabs(y - axis.z_), 1e-6);
00092     ASSERT_LT(fabs(ang - angle), 1e-6);
00093   }
00094 
00095   // Test forward up style constructor
00096   for (int i = 0; i < 3; ++i)
00097   {
00098     const mcl_3dl::Vec3 fw((i == 0) ? 1.0 : 0.0, (i == 1) ? 1.0 : 0.0, (i == 2) ? 1.0 : 0.0);
00099     for (int j = 0; j < 3; ++j)
00100     {
00101       const mcl_3dl::Vec3 up((j == 0) ? 1.0 : 0.0, (j == 1) ? 1.0 : 0.0, (j == 2) ? 1.0 : 0.0);
00102 
00103       if (fw == up)
00104         continue;
00105 
00106       const mcl_3dl::Quat q(fw, up);
00107 
00108       // Rotate forward and up vectors and validate
00109       const mcl_3dl::Vec3 f = q * mcl_3dl::Vec3(1.0, 0.0, 0.0);
00110       const mcl_3dl::Vec3 u = q * mcl_3dl::Vec3(0.0, 0.0, 1.0);
00111 
00112       ASSERT_LT(fabs(f.x_ - fw.x_), 1e-6);
00113       ASSERT_LT(fabs(f.y_ - fw.y_), 1e-6);
00114       ASSERT_LT(fabs(f.z_ - fw.z_), 1e-6);
00115       ASSERT_LT(fabs(u.x_ - up.x_), 1e-6);
00116       ASSERT_LT(fabs(u.y_ - up.y_), 1e-6);
00117       ASSERT_LT(fabs(u.z_ - up.z_), 1e-6);
00118     }
00119   }
00120 }
00121 
00122 TEST(Quat, Operators)
00123 {
00124   const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
00125 
00126   // Test ==,!= operators
00127   ASSERT_TRUE(mcl_3dl::Quat(1.0, 2.0, 3.0, 4.0) == a);
00128   ASSERT_FALSE(mcl_3dl::Quat(1.0, 2.0, 3.0, 4.0) != a);
00129 
00130   for (uint32_t i = 1; i < (1 << 4); ++i)
00131   {
00132     const float xp = (i & (1 << 0)) ? 0.1 : 0.0;
00133     const float yp = (i & (1 << 1)) ? 0.1 : 0.0;
00134     const float zp = (i & (1 << 2)) ? 0.1 : 0.0;
00135     const float wp = (i & (1 << 3)) ? 0.1 : 0.0;
00136     ASSERT_TRUE(mcl_3dl::Quat(1.0 + xp, 2.0 + yp, 3.0 + zp, 4.0 + wp) != a);
00137     ASSERT_FALSE(mcl_3dl::Quat(1.0 + xp, 2.0 + yp, 3.0 + zp, 4.0 + wp) == a);
00138   }
00139 
00140   // Test +, -, +=, -= operators
00141   const mcl_3dl::Quat adding(0.5, -0.5, 1.0, -1.0);
00142   mcl_3dl::Quat a_plus = a;
00143   mcl_3dl::Quat a_minus = a;
00144   a_plus += adding;
00145   a_minus -= adding;
00146   ASSERT_TRUE(a + adding == mcl_3dl::Quat(1.5, 1.5, 4.0, 3.0));
00147   ASSERT_TRUE(a + adding == a_plus);
00148   ASSERT_TRUE(a - adding == mcl_3dl::Quat(0.5, 2.5, 2.0, 5.0));
00149   ASSERT_TRUE(a - adding == a_minus);
00150 
00151   // Test -() operator
00152   ASSERT_TRUE(-a == mcl_3dl::Quat(-1.0, -2.0, -3.0, -4.0));
00153 
00154   // Test scalar *, / operators
00155   mcl_3dl::Quat a_mul = a;
00156   mcl_3dl::Quat a_div = a;
00157   a_mul *= 0.5;
00158   a_div /= 2.0;
00159   ASSERT_TRUE(a * 0.5 == mcl_3dl::Quat(0.5, 1.0, 1.5, 2.0));
00160   ASSERT_TRUE(a / 2.0 == a * 0.5);
00161   ASSERT_TRUE(a * 0.5 == a_mul);
00162   ASSERT_TRUE(a / 2.0 == a_div);
00163 }
00164 
00165 TEST(Quat, Norm)
00166 {
00167   // Check norm operations
00168   const mcl_3dl::Quat a(1.0, 2.0, 3.0, 4.0);
00169   const mcl_3dl::Quat b(-4.0, 5.0, 6.0, -7.0);
00170   ASSERT_LT(fabs(a.norm() - 5.477226), 1e-6);
00171   ASSERT_LT(fabs(b.norm() - 11.224972), 1e-6);
00172   ASSERT_LT(fabs(a.normalized().norm() - 1.0), 1e-6);
00173   ASSERT_LT(fabs(b.normalized().norm() - 1.0), 1e-6);
00174 }
00175 
00176 TEST(Quat, Products)
00177 {
00178   // Check cross and dot products
00179   const int num_samples = 8;
00180   const mcl_3dl::Quat samples[num_samples] =
00181       {
00182         mcl_3dl::Quat(mcl_3dl::Vec3(1.5, 2.5, 3.5), 0.5),
00183         mcl_3dl::Quat(mcl_3dl::Vec3(-0.5, 1.0, 1.0), 1.0),
00184         mcl_3dl::Quat(mcl_3dl::Vec3(0.5, -1.0, 2.0), 1.5),
00185         mcl_3dl::Quat(mcl_3dl::Vec3(0.5, 1.0, -2.0), 2.0),
00186         mcl_3dl::Quat(mcl_3dl::Vec3(-2.0, -5.0, 4.0), 2.5),
00187         mcl_3dl::Quat(mcl_3dl::Vec3(2.0, -5.0, -4.0), -1.0),
00188         mcl_3dl::Quat(mcl_3dl::Vec3(-2.0, 5.0, -4.0), -1.5),
00189         mcl_3dl::Quat(mcl_3dl::Vec3(-3.0, -1.0, -2.0), -2.0)
00190       };
00191 
00192   // Check inverse
00193   for (int i = 0; i < num_samples; ++i)
00194   {
00195     const mcl_3dl::Quat inv = samples[i].inv();
00196     const mcl_3dl::Quat ident0 = inv * samples[i];
00197     const mcl_3dl::Quat ident1 = samples[i] * inv;
00198 
00199     ASSERT_LT(fabs(ident0.x_), 1e-6);
00200     ASSERT_LT(fabs(ident0.y_), 1e-6);
00201     ASSERT_LT(fabs(ident0.z_), 1e-6);
00202     ASSERT_LT(fabs(ident0.w_ - 1.0), 1e-6);
00203     ASSERT_LT(fabs(ident1.x_), 1e-6);
00204     ASSERT_LT(fabs(ident1.y_), 1e-6);
00205     ASSERT_LT(fabs(ident1.z_), 1e-6);
00206     ASSERT_LT(fabs(ident1.w_ - 1.0), 1e-6);
00207   }
00208 
00209   // Check rotate axis
00210   for (int i = 0; i < num_samples; ++i)
00211   {
00212     for (int j = 0; j < num_samples; ++j)
00213     {
00214       mcl_3dl::Vec3 a_axis;
00215       float a_ang;
00216       samples[i].getAxisAng(a_axis, a_ang);
00217 
00218       mcl_3dl::Quat a(a_axis, a_ang);
00219       const mcl_3dl::Quat& b = samples[j];
00220 
00221       const mcl_3dl::Vec3 rotated_axis = b * a_axis;
00222       a.rotateAxis(b);
00223 
00224       mcl_3dl::Vec3 a_axis2;
00225       float a_ang2;
00226       a.getAxisAng(a_axis2, a_ang2);
00227 
00228       ASSERT_LT(fabs(a_axis2.x_ - rotated_axis.x_), 1e-6);
00229       ASSERT_LT(fabs(a_axis2.y_ - rotated_axis.y_), 1e-6);
00230       ASSERT_LT(fabs(a_axis2.z_ - rotated_axis.z_), 1e-6);
00231       ASSERT_LT(fabs(a_ang - a_ang2), 1e-6);
00232     }
00233   }
00234 
00235   // Check vector rotation
00236   const int num_vecs = 3;
00237   const mcl_3dl::Vec3 v[num_vecs] =
00238       {
00239         mcl_3dl::Vec3(1.0, 0.0, 0.0),
00240         mcl_3dl::Vec3(0.0, 1.0, 0.0),
00241         mcl_3dl::Vec3(0.0, 0.0, 1.0)
00242       };
00243   const int num_rots = 3;
00244   const mcl_3dl::Quat r[num_rots] =
00245       {
00246         mcl_3dl::Quat(mcl_3dl::Vec3(1.0, 0.0, 0.0), M_PI / 2.0),
00247         mcl_3dl::Quat(mcl_3dl::Vec3(0.0, 1.0, 0.0), -M_PI / 2.0),
00248         mcl_3dl::Quat(mcl_3dl::Vec3(0.0, 0.0, 1.0), -M_PI / 2.0)
00249       };
00250   const mcl_3dl::Vec3 v_ans[3][3] =
00251       {
00252         mcl_3dl::Vec3(1.0, 0.0, 0.0),
00253         mcl_3dl::Vec3(0.0, 0.0, 1.0),
00254         mcl_3dl::Vec3(0.0, -1.0, 0.0),
00255         mcl_3dl::Vec3(0.0, 0.0, 1.0),
00256         mcl_3dl::Vec3(0.0, 1.0, 0.0),
00257         mcl_3dl::Vec3(-1.0, 0.0, 0.0),
00258         mcl_3dl::Vec3(0.0, -1.0, 0.0),
00259         mcl_3dl::Vec3(1.0, 0.0, 0.0),
00260         mcl_3dl::Vec3(0.0, 0.0, 1.0)
00261       };
00262   for (int i = 0; i < num_vecs; ++i)
00263   {
00264     for (int j = 0; j < num_rots; ++j)
00265     {
00266       const mcl_3dl::Vec3 result = r[j] * v[i];
00267       ASSERT_LT(fabs(result.x_ - v_ans[j][i].x_), 1e-6);
00268       ASSERT_LT(fabs(result.y_ - v_ans[j][i].y_), 1e-6);
00269       ASSERT_LT(fabs(result.z_ - v_ans[j][i].z_), 1e-6);
00270     }
00271   }
00272 
00273   for (int i = 0; i < num_samples; ++i)
00274   {
00275     for (int j = 0; j < num_samples; ++j)
00276     {
00277       const mcl_3dl::Quat& a = samples[i];
00278       const mcl_3dl::Quat& b = samples[j];
00279 
00280       // Check dot products based on the distributive property
00281       ASSERT_LT((a - b).dot(a - b) - a.dot(a) - b.dot(b) + 2.0 * a.dot(b), 1e-6);
00282 
00283       // Check mcl_3dl::Quat by mcl_3dl::Quat products
00284       const mcl_3dl::Vec3 v(1.0, 2.0, 3.0);
00285       const mcl_3dl::Vec3 v1 = (a * b) * v;
00286       const mcl_3dl::Vec3 v2 = a * (b * v);
00287       ASSERT_LT(fabs(v1.x_ - v2.x_), 1e-6);
00288       ASSERT_LT(fabs(v1.y_ - v2.y_), 1e-6);
00289       ASSERT_LT(fabs(v1.z_ - v2.z_), 1e-6);
00290     }
00291   }
00292 }
00293 
00294 int main(int argc, char** argv)
00295 {
00296   testing::InitGoogleTest(&argc, argv);
00297 
00298   return RUN_ALL_TESTS();
00299 }


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 20 2019 20:04:43