Program Listing for File transform.h
↰ Return to documentation for file (include/coal/math/transform.h
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2015, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef COAL_TRANSFORM_H
#define COAL_TRANSFORM_H
#include "coal/fwd.hh"
#include "coal/data_types.h"
namespace coal {
COAL_DEPRECATED typedef Eigen::Quaternion<CoalScalar> Quaternion3f;
typedef Eigen::Quaternion<CoalScalar> Quatf;
static inline std::ostream& operator<<(std::ostream& o, const Quatf& q) {
o << "(" << q.w() << " " << q.x() << " " << q.y() << " " << q.z() << ")";
return o;
}
class COAL_DLLAPI Transform3s {
Matrix3s R;
Vec3s T;
public:
Transform3s() {
setIdentity(); // set matrix_set true
}
static Transform3s Identity() { return Transform3s(); }
template <typename Matrixx3Like, typename Vector3Like>
Transform3s(const Eigen::MatrixBase<Matrixx3Like>& R_,
const Eigen::MatrixBase<Vector3Like>& T_)
: R(R_), T(T_) {}
template <typename Vector3Like>
Transform3s(const Quatf& q_, const Eigen::MatrixBase<Vector3Like>& T_)
: R(q_.toRotationMatrix()), T(T_) {}
Transform3s(const Matrix3s& R_) : R(R_), T(Vec3s::Zero()) {}
Transform3s(const Quatf& q_) : R(q_), T(Vec3s::Zero()) {}
Transform3s(const Vec3s& T_) : R(Matrix3s::Identity()), T(T_) {}
Transform3s(const Transform3s& tf) : R(tf.R), T(tf.T) {}
Transform3s& operator=(const Transform3s& tf) {
R = tf.R;
T = tf.T;
return *this;
}
inline const Vec3s& getTranslation() const { return T; }
inline const Vec3s& translation() const { return T; }
inline Vec3s& translation() { return T; }
inline const Matrix3s& getRotation() const { return R; }
inline const Matrix3s& rotation() const { return R; }
inline Matrix3s& rotation() { return R; }
inline Quatf getQuatRotation() const { return Quatf(R); }
template <typename Matrix3Like, typename Vector3Like>
inline void setTransform(const Eigen::MatrixBase<Matrix3Like>& R_,
const Eigen::MatrixBase<Vector3Like>& T_) {
R.noalias() = R_;
T.noalias() = T_;
}
inline void setTransform(const Quatf& q_, const Vec3s& T_) {
R = q_.toRotationMatrix();
T = T_;
}
template <typename Derived>
inline void setRotation(const Eigen::MatrixBase<Derived>& R_) {
R.noalias() = R_;
}
template <typename Derived>
inline void setTranslation(const Eigen::MatrixBase<Derived>& T_) {
T.noalias() = T_;
}
inline void setQuatRotation(const Quatf& q_) { R = q_.toRotationMatrix(); }
template <typename Derived>
inline Vec3s transform(const Eigen::MatrixBase<Derived>& v) const {
return R * v + T;
}
template <typename Derived>
inline Vec3s inverseTransform(const Eigen::MatrixBase<Derived>& v) const {
return R.transpose() * (v - T);
}
inline Transform3s& inverseInPlace() {
R.transposeInPlace();
T = -R * T;
return *this;
}
inline Transform3s inverse() {
return Transform3s(R.transpose(), -R.transpose() * T);
}
inline Transform3s inverseTimes(const Transform3s& other) const {
return Transform3s(R.transpose() * other.R, R.transpose() * (other.T - T));
}
inline const Transform3s& operator*=(const Transform3s& other) {
T += R * other.T;
R *= other.R;
return *this;
}
inline Transform3s operator*(const Transform3s& other) const {
return Transform3s(R * other.R, R * other.T + T);
}
inline bool isIdentity(
const CoalScalar& prec =
Eigen::NumTraits<CoalScalar>::dummy_precision()) const {
return R.isIdentity(prec) && T.isZero(prec);
}
inline void setIdentity() {
R.setIdentity();
T.setZero();
}
static Transform3s Random() {
Transform3s tf = Transform3s();
tf.setRandom();
return tf;
}
inline void setRandom();
bool operator==(const Transform3s& other) const {
return (R == other.getRotation()) && (T == other.getTranslation());
}
bool operator!=(const Transform3s& other) const { return !(*this == other); }
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
template <typename Derived>
inline Quatf fromAxisAngle(const Eigen::MatrixBase<Derived>& axis,
CoalScalar angle) {
return Quatf(Eigen::AngleAxis<CoalScalar>(angle, axis));
}
inline Quatf uniformRandomQuaternion() {
// Rotational part
const CoalScalar u1 = (CoalScalar)rand() / RAND_MAX;
const CoalScalar u2 = (CoalScalar)rand() / RAND_MAX;
const CoalScalar u3 = (CoalScalar)rand() / RAND_MAX;
const CoalScalar mult1 = std::sqrt(CoalScalar(1.0) - u1);
const CoalScalar mult2 = std::sqrt(u1);
static const CoalScalar PI_value = static_cast<CoalScalar>(EIGEN_PI);
CoalScalar s2 = std::sin(2 * PI_value * u2);
CoalScalar c2 = std::cos(2 * PI_value * u2);
CoalScalar s3 = std::sin(2 * PI_value * u3);
CoalScalar c3 = std::cos(2 * PI_value * u3);
Quatf q;
q.w() = mult1 * s2;
q.x() = mult1 * c2;
q.y() = mult2 * s3;
q.z() = mult2 * c3;
return q;
}
inline void Transform3s::setRandom() {
const Quatf q = uniformRandomQuaternion();
this->rotation() = q.matrix();
this->translation().setRandom();
}
inline Matrix3s constructOrthonormalBasisFromVector(const Vec3s& vec) {
Matrix3s basis = Matrix3s::Zero();
basis.col(2) = vec.normalized();
basis.col(1) = -vec.unitOrthogonal();
basis.col(0) = basis.col(1).cross(vec);
return basis;
}
} // namespace coal
#endif