math.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #define _USE_MATH_DEFINES
37 #include <cmath>
38 
39 #define BOOST_TEST_MODULE COAL_MATH
40 #include <boost/test/included/unit_test.hpp>
41 
42 #include "coal/data_types.h"
43 #include "coal/math/transform.h"
44 
46 #include "coal/internal/tools.h"
47 
48 using namespace coal;
49 
50 BOOST_AUTO_TEST_CASE(vec_test_eigen_vec64) {
51  Vec3s v1(1.0, 2.0, 3.0);
52  BOOST_CHECK(v1[0] == 1.0);
53  BOOST_CHECK(v1[1] == 2.0);
54  BOOST_CHECK(v1[2] == 3.0);
55 
56  Vec3s v2 = v1;
57  Vec3s v3(3.3, 4.3, 5.3);
58  v1 += v3;
59  BOOST_CHECK(isEqual(v1, v2 + v3));
60  v1 -= v3;
61  BOOST_CHECK(isEqual(v1, v2));
62  v1 -= v3;
63  BOOST_CHECK(isEqual(v1, v2 - v3));
64  v1 += v3;
65 
66  v1.array() *= v3.array();
67  BOOST_CHECK(isEqual(v1, v2.cwiseProduct(v3)));
68  v1.array() /= v3.array();
69  BOOST_CHECK(isEqual(v1, v2));
70  v1.array() /= v3.array();
71  BOOST_CHECK(isEqual(v1, v2.cwiseQuotient(v3)));
72  v1.array() *= v3.array();
73 
74  v1 *= 2.0;
75  BOOST_CHECK(isEqual(v1, v2 * 2.0));
76  v1 /= 2.0;
77  BOOST_CHECK(isEqual(v1, v2));
78  v1 /= 2.0;
79  BOOST_CHECK(isEqual(v1, v2 / 2.0));
80  v1 *= 2.0;
81 
82  v1.array() += 2.0;
83  BOOST_CHECK(isEqual(v1, (v2.array() + 2.0).matrix()));
84  v1.array() -= 2.0;
85  BOOST_CHECK(isEqual(v1, v2));
86  v1.array() -= 2.0;
87  BOOST_CHECK(isEqual(v1, (v2.array() - 2.0).matrix()));
88  v1.array() += 2.0;
89 
90  BOOST_CHECK(isEqual((-Vec3s(1.0, 2.0, 3.0)), Vec3s(-1.0, -2.0, -3.0)));
91 
92  v1 = Vec3s(1.0, 2.0, 3.0);
93  v2 = Vec3s(3.0, 4.0, 5.0);
94  BOOST_CHECK(isEqual((v1.cross(v2)), Vec3s(-2.0, 4.0, -2.0)));
95  BOOST_CHECK(std::abs(v1.dot(v2) - 26) < 1e-5);
96 
97  v1 = Vec3s(3.0, 4.0, 5.0);
98  BOOST_CHECK(std::abs(v1.squaredNorm() - 50) < 1e-5);
99  BOOST_CHECK(std::abs(v1.norm() - sqrt(50)) < 1e-5);
100  BOOST_CHECK(isEqual(v1.normalized(), v1 / v1.norm()));
101 
102  v1 = Vec3s(1.0, 2.0, 3.0);
103  v2 = Vec3s(3.0, 4.0, 5.0);
104  BOOST_CHECK(isEqual(v1.cross(v2), Vec3s(-2.0, 4.0, -2.0)));
105  BOOST_CHECK(v1.dot(v2) == 26);
106 }
107 
109  return 2 * vec.dot(input) * vec + (w * w - vec.dot(vec)) * input +
110  2 * w * vec.cross(input);
111 }
112 
113 BOOST_AUTO_TEST_CASE(quaternion) {
114  Quatf q1(Quatf::Identity()), q2, q3;
115  q2 = fromAxisAngle(Vec3s(0, 0, 1), M_PI / 2);
116  q3 = q2.inverse();
117 
118  Vec3s v(1, -1, 0);
119 
120  BOOST_CHECK(isEqual(v, q1 * v));
121  BOOST_CHECK(isEqual(Vec3s(1, 1, 0), q2 * v));
122  BOOST_CHECK(
123  isEqual(rotate(v, q3.w(), Vec3s(q3.x(), q3.y(), q3.z())), q3 * v));
124 }
125 
127  Quatf q = fromAxisAngle(Vec3s(0, 0, 1), M_PI / 2);
128  Vec3s T(0, 1, 2);
129  Transform3s tf(q, T);
130 
131  Vec3s v(1, -1, 0);
132 
133  BOOST_CHECK(isEqual(q * v + T, q * v + T));
134 
135  Vec3s rv(q * v);
136  // typename Transform3s::transform_return_type<Vec3s>::type output =
137  // tf * v;
138  // std::cout << rv << std::endl;
139  // std::cout << output.lhs() << std::endl;
140  BOOST_CHECK(isEqual(rv + T, tf.transform(v)));
141 }
142 
143 BOOST_AUTO_TEST_CASE(random_transform) {
144  for (size_t i = 0; i < 100; ++i) {
145  const Transform3s tf = Transform3s::Random();
146  BOOST_CHECK((tf.inverseTimes(tf)).isIdentity());
147  }
148 }
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
intersect.h
coal::Transform3s::Random
static Transform3s Random()
return a random transform
Definition: coal/math/transform.h:205
coal::Transform3s::transform
Vec3s transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: coal/math/transform.h:152
q2
q2
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
collision.q1
tuple q1
Definition: scripts/collision.py:32
vec
vec
coal::Quatf
Eigen::Quaternion< CoalScalar > Quatf
Definition: coal/math/transform.h:47
coal::Transform3s::inverseTimes
Transform3s inverseTimes(const Transform3s &other) const
inverse the transform and multiply with another
Definition: coal/math/transform.h:175
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(vec_test_eigen_vec64)
Definition: math.cpp:50
transform.h
coal::isEqual
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100)
Definition: coal/internal/tools.h:204
coal::transform
COAL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3s &tf)
Definition: geometric_shapes_utility.cpp:248
q
q
tools.h
coal::rotate
static AABB rotate(const AABB &aabb, const Matrix3s &R)
Definition: coal/BV/AABB.h:240
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::fromAxisAngle
Quatf fromAxisAngle(const Eigen::MatrixBase< Derived > &axis, CoalScalar angle)
Definition: coal/math/transform.h:224
obb.v
list v
Definition: obb.py:48


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58