Skip to content

Commit

Permalink
Deprecating Quaternion3f in favor of Quatf
Browse files Browse the repository at this point in the history
  • Loading branch information
lmontaut committed Jan 2, 2024
1 parent c2c84e3 commit 2307511
Show file tree
Hide file tree
Showing 10 changed files with 38 additions and 39 deletions.
24 changes: 12 additions & 12 deletions include/hpp/fcl/math/transform.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,16 @@
#ifndef HPP_FCL_TRANSFORM_H
#define HPP_FCL_TRANSFORM_H

#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/data_types.h>

namespace hpp {
namespace fcl {

typedef Eigen::Quaternion<FCL_REAL> Quaternion3f;
HPP_FCL_DEPRECATED typedef Eigen::Quaternion<FCL_REAL> Quaternion3f;
typedef Eigen::Quaternion<FCL_REAL> Quatf;

static inline std::ostream& operator<<(std::ostream& o, const Quaternion3f& q) {
static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) {
o << "(" << q.w() << " " << q.x() << " " << q.y() << " " << q.z() << ")";
return o;
}
Expand Down Expand Up @@ -74,14 +76,14 @@ class HPP_FCL_DLLAPI Transform3f {

/// @brief Construct transform from rotation and translation
template <typename Vector3Like>
Transform3f(const Quaternion3f& q_, const Eigen::MatrixBase<Vector3Like>& T_)
Transform3f(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
: R(q_.toRotationMatrix()), T(T_) {}

/// @brief Construct transform from rotation
Transform3f(const Matrix3f& R_) : R(R_), T(Vec3f::Zero()) {}

/// @brief Construct transform from rotation
Transform3f(const Quaternion3f& q_) : R(q_), T(Vec3f::Zero()) {}
Transform3f(const Quatf& q_) : R(q_), T(Vec3f::Zero()) {}

/// @brief Construct transform from translation
Transform3f(const Vec3f& T_) : R(Matrix3f::Identity()), T(T_) {}
Expand Down Expand Up @@ -115,7 +117,7 @@ class HPP_FCL_DLLAPI Transform3f {
inline Matrix3f& rotation() { return R; }

/// @brief get quaternion
inline Quaternion3f getQuatRotation() const { return Quaternion3f(R); }
inline Quatf getQuatRotation() const { return Quatf(R); }

/// @brief set transform from rotation and translation
template <typename Matrix3Like, typename Vector3Like>
Expand All @@ -126,7 +128,7 @@ class HPP_FCL_DLLAPI Transform3f {
}

/// @brief set transform from rotation and translation
inline void setTransform(const Quaternion3f& q_, const Vec3f& T_) {
inline void setTransform(const Quatf& q_, const Vec3f& T_) {
R = q_.toRotationMatrix();
T = T_;
}
Expand All @@ -144,9 +146,7 @@ class HPP_FCL_DLLAPI Transform3f {
}

/// @brief set transform from rotation
inline void setQuatRotation(const Quaternion3f& q_) {
R = q_.toRotationMatrix();
}
inline void setQuatRotation(const Quatf& q_) { R = q_.toRotationMatrix(); }

/// @brief transform a given vector by the transform
template <typename Derived>
Expand Down Expand Up @@ -206,9 +206,9 @@ class HPP_FCL_DLLAPI Transform3f {
};

template <typename Derived>
inline Quaternion3f fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
FCL_REAL angle) {
return Quaternion3f(Eigen::AngleAxis<FCL_REAL>(angle, axis));
inline Quatf fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
FCL_REAL angle) {
return Quatf(Eigen::AngleAxis<FCL_REAL>(angle, axis));
}

} // namespace fcl
Expand Down
7 changes: 3 additions & 4 deletions python/math.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,9 @@ void exposeMaths() {
.def(dv::init<Transform3f>())
.def(dv::init<Transform3f, const Matrix3f::MatrixBase&,
const Vec3f::MatrixBase&>())
.def(dv::init<Transform3f, const Quaternion3f&,
const Vec3f::MatrixBase&>())
.def(dv::init<Transform3f, const Quatf&, const Vec3f::MatrixBase&>())
.def(dv::init<Transform3f, const Matrix3f&>())
.def(dv::init<Transform3f, const Quaternion3f&>())
.def(dv::init<Transform3f, const Quatf&>())
.def(dv::init<Transform3f, const Vec3f&>())
.def(dv::init<Transform3f, const Transform3f&>())

Expand All @@ -102,7 +101,7 @@ void exposeMaths() {
&Transform3f::setTransform<Matrix3f, Vec3f>))
.def(dv::member_func(
"setTransform",
static_cast<void (Transform3f::*)(const Quaternion3f&, const Vec3f&)>(
static_cast<void (Transform3f::*)(const Quatf&, const Vec3f&)>(
&Transform3f::setTransform)))
.def(dv::member_func("setIdentity", &Transform3f::setIdentity))
.def(dv::member_func("Identity", &Transform3f::Identity))
Expand Down
4 changes: 2 additions & 2 deletions src/BV/OBB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,10 +116,10 @@ inline OBB merge_largedist(const OBB& b1, const OBB& b2) {
inline OBB merge_smalldist(const OBB& b1, const OBB& b2) {
OBB b;
b.To = (b1.To + b2.To) * 0.5;
Quaternion3f q0(b1.axes), q1(b2.axes);
Quatf q0(b1.axes), q1(b2.axes);
if (q0.dot(q1) < 0) q1.coeffs() *= -1;

Quaternion3f q((q0.coeffs() + q1.coeffs()).normalized());
Quatf q((q0.coeffs() + q1.coeffs()).normalized());
b.axes = q.toRotationMatrix();

Vec3f vertex[8], diff;
Expand Down
4 changes: 2 additions & 2 deletions test/bvh_models.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,15 +206,15 @@ void testBVHModelTriangles() {

pose.setTranslation(Vec3f(0, 0, 0));
FCL_REAL sqrt2_2 = std::sqrt(2) / 2;
pose.setQuatRotation(Quaternion3f(sqrt2_2, sqrt2_2, 0, 0));
pose.setQuatRotation(Quatf(sqrt2_2, sqrt2_2, 0, 0));
cropped.reset(BVHExtract(*model, pose, aabb));
BOOST_REQUIRE(cropped);
BOOST_CHECK(cropped->build_state == BVH_BUILD_STATE_PROCESSED);
BOOST_CHECK_EQUAL(cropped->num_vertices, model->num_vertices - 6);
BOOST_CHECK_EQUAL(cropped->num_tris, model->num_tris - 2);

pose.setTranslation(-Vec3f(1, 1, 1));
pose.setQuatRotation(Quaternion3f::Identity());
pose.setQuatRotation(Quatf::Identity());
cropped.reset(BVHExtract(*model, pose, aabb));
BOOST_CHECK(!cropped);

Expand Down
14 changes: 7 additions & 7 deletions test/geometric_shapes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,12 +239,12 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_cylinderbox) {
Box s2(1.6, 0.6, 0.025);

Transform3f tf1(
Quaternion3f(0.5279170511703305, -0.50981118132505521,
-0.67596178682051911, 0.0668715876735793),
Quatf(0.5279170511703305, -0.50981118132505521, -0.67596178682051911,
0.0668715876735793),
Vec3f(0.041218354748013122, 1.2022554710435607, 0.77338855025700015));

Transform3f tf2(
Quaternion3f(0.70738826916719977, 0, 0, 0.70682518110536596),
Quatf(0.70738826916719977, 0, 0, 0.70682518110536596),
Vec3f(-0.29936284351096382, 0.80023864435868775, 0.71750000000000003));

GJKSolver solver;
Expand Down Expand Up @@ -285,8 +285,8 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_cylinderbox) {
s1 = Cylinder(0.06, 0.1);
tf1.setTranslation(
Vec3f(-0.66734052046473924, 0.22219183277457269, 0.76825248755616293));
tf1.setQuatRotation(Quaternion3f(0.52613359459338371, 0.32189408354839893,
0.70415587451837913, -0.35175580165512249));
tf1.setQuatRotation(Quatf(0.52613359459338371, 0.32189408354839893,
0.70415587451837913, -0.35175580165512249));
res = solver.shapeDistance(s1, tf1, s2, tf2, distance, p1, p2, normal);
}

Expand Down Expand Up @@ -450,7 +450,7 @@ BOOST_AUTO_TEST_CASE(shapeIntersection_boxbox) {
// FCL_REAL depth;
Vec3f normal;

Quaternion3f q;
Quatf q;
q = AngleAxis((FCL_REAL)3.140 / 6, UnitZ);

tf1 = Transform3f();
Expand Down Expand Up @@ -3402,7 +3402,7 @@ BOOST_AUTO_TEST_CASE(shapeIntersectionGJK_boxbox) {
// FCL_REAL depth;
Vec3f normal;

Quaternion3f q;
Quatf q;
q = AngleAxis((FCL_REAL)3.140 / 6, UnitZ);

tf1 = Transform3f();
Expand Down
10 changes: 5 additions & 5 deletions test/gjk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ using hpp::fcl::FCL_REAL;
using hpp::fcl::GJKSolver;
using hpp::fcl::GJKVariant;
using hpp::fcl::Matrix3f;
using hpp::fcl::Quaternion3f;
using hpp::fcl::Quatf;
using hpp::fcl::Transform3f;
using hpp::fcl::TriangleP;
using hpp::fcl::Vec3f;
Expand Down Expand Up @@ -103,8 +103,8 @@ void test_gjk_distance_triangle_triangle(
Q2_loc = Vec3f(-10.926, -1.284259033203125, 3.7281499023437501);
Q3_loc = Vec3f(-10.926, -1.2866180419921875, 3.72335400390625);
Transform3f tf(
Quaternion3f(-0.42437287410898855, -0.26862477561450587,
-0.46249645019513175, 0.73064726592483387),
Quatf(-0.42437287410898855, -0.26862477561450587,
-0.46249645019513175, 0.73064726592483387),
Vec3f(-12.824601270753471, -1.6840516940066426, 3.8914453043793844));
tf1 = tf;
} else if (i == 1) {
Expand Down Expand Up @@ -323,8 +323,8 @@ void test_gjk_unit_sphere(FCL_REAL center_distance, Vec3f ray,
Sphere sphere(1.);

typedef Eigen::Matrix<FCL_REAL, 4, 1> Vec4f;
Transform3f tf0(Quaternion3f(Vec4f::Random().normalized()), Vec3f::Zero()),
tf1(Quaternion3f(Vec4f::Random().normalized()), center_distance * ray);
Transform3f tf0(Quatf(Vec4f::Random().normalized()), Vec3f::Zero()),
tf1(Quatf(Vec4f::Random().normalized()), center_distance * ray);

details::MinkowskiDiff shape;
shape.set(&sphere, &sphere, tf0, tf1);
Expand Down
4 changes: 2 additions & 2 deletions test/math.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ Vec3f rotate(Vec3f input, FCL_REAL w, Vec3f vec) {
}

BOOST_AUTO_TEST_CASE(quaternion) {
Quaternion3f q1(Quaternion3f::Identity()), q2, q3;
Quatf q1(Quatf::Identity()), q2, q3;
q2 = fromAxisAngle(Vec3f(0, 0, 1), M_PI / 2);
q3 = q2.inverse();

Expand All @@ -124,7 +124,7 @@ BOOST_AUTO_TEST_CASE(quaternion) {
}

BOOST_AUTO_TEST_CASE(transform) {
Quaternion3f q = fromAxisAngle(Vec3f(0, 0, 1), M_PI / 2);
Quatf q = fromAxisAngle(Vec3f(0, 0, 1), M_PI / 2);
Vec3f T(0, 1, 2);
Transform3f tf(q, T);

Expand Down
4 changes: 2 additions & 2 deletions test/obb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void randomTransform(Matrix3f& B, Vec3f& T, const Vec3f& a, const Vec3f& b,
T = (Vec3f::Random() / sqrt(3)) * 1.5 * N;
// T.setZero();

Quaternion3f q;
Quatf q;
q.coeffs().setRandom();
q.normalize();
B = q;
Expand Down Expand Up @@ -1204,7 +1204,7 @@ BenchmarkResult benchmark_obb_case(const Matrix3f& B, const Vec3f& T,
result.failure = false;
}
if (result.failure) {
std::cerr << "\nR = " << Quaternion3f(B).coeffs().transpose().format(py_fmt)
std::cerr << "\nR = " << Quatf(B).coeffs().transpose().format(py_fmt)
<< "\nT = " << T.transpose().format(py_fmt)
<< "\na = " << a.transpose().format(py_fmt)
<< "\nb = " << b.transpose().format(py_fmt)
Expand Down
4 changes: 2 additions & 2 deletions test/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,8 +365,8 @@ std::string getNodeTypeName(NODE_TYPE node_type) {
return std::string("invalid");
}

Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z) {
Quaternion3f q;
Quatf makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z) {
Quatf q;
q.w() = w;
q.x() = x;
q.y() = y;
Expand Down
2 changes: 1 addition & 1 deletion test/utility.h
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2,

std::string getNodeTypeName(NODE_TYPE node_type);

Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z);
Quatf makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z);

std::ostream& operator<<(std::ostream& os, const Transform3f& tf);

Expand Down

0 comments on commit 2307511

Please sign in to comment.