rigid_transform.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_TRANSFORM_RIGID_TRANSFORM_H_
00018 #define CARTOGRAPHER_TRANSFORM_RIGID_TRANSFORM_H_
00019 
00020 #include <cmath>
00021 #include <iostream>
00022 #include <string>
00023 
00024 #include "Eigen/Core"
00025 #include "Eigen/Geometry"
00026 #include "absl/strings/substitute.h"
00027 #include "cartographer/common/lua_parameter_dictionary.h"
00028 #include "cartographer/common/math.h"
00029 #include "cartographer/common/port.h"
00030 
00031 namespace cartographer {
00032 namespace transform {
00033 
00034 template <typename FloatType>
00035 class Rigid2 {
00036  public:
00037   using Vector = Eigen::Matrix<FloatType, 2, 1>;
00038   using Rotation2D = Eigen::Rotation2D<FloatType>;
00039 
00040   Rigid2() : translation_(Vector::Zero()), rotation_(Rotation2D::Identity()) {}
00041   Rigid2(const Vector& translation, const Rotation2D& rotation)
00042       : translation_(translation), rotation_(rotation) {}
00043   Rigid2(const Vector& translation, const double rotation)
00044       : translation_(translation), rotation_(rotation) {}
00045 
00046   static Rigid2 Rotation(const double rotation) {
00047     return Rigid2(Vector::Zero(), rotation);
00048   }
00049 
00050   static Rigid2 Rotation(const Rotation2D& rotation) {
00051     return Rigid2(Vector::Zero(), rotation);
00052   }
00053 
00054   static Rigid2 Translation(const Vector& vector) {
00055     return Rigid2(vector, Rotation2D::Identity());
00056   }
00057 
00058   static Rigid2<FloatType> Identity() { return Rigid2<FloatType>(); }
00059 
00060   template <typename OtherType>
00061   Rigid2<OtherType> cast() const {
00062     return Rigid2<OtherType>(translation_.template cast<OtherType>(),
00063                              rotation_.template cast<OtherType>());
00064   }
00065 
00066   const Vector& translation() const { return translation_; }
00067 
00068   Rotation2D rotation() const { return rotation_; }
00069 
00070   double normalized_angle() const {
00071     return common::NormalizeAngleDifference(rotation().angle());
00072   }
00073 
00074   Rigid2 inverse() const {
00075     const Rotation2D rotation = rotation_.inverse();
00076     const Vector translation = -(rotation * translation_);
00077     return Rigid2(translation, rotation);
00078   }
00079 
00080   std::string DebugString() const {
00081     return absl::Substitute("{ t: [$0, $1], r: [$2] }", translation().x(),
00082                             translation().y(), rotation().angle());
00083   }
00084 
00085  private:
00086   Vector translation_;
00087   Rotation2D rotation_;
00088 };
00089 
00090 template <typename FloatType>
00091 Rigid2<FloatType> operator*(const Rigid2<FloatType>& lhs,
00092                             const Rigid2<FloatType>& rhs) {
00093   return Rigid2<FloatType>(
00094       lhs.rotation() * rhs.translation() + lhs.translation(),
00095       lhs.rotation() * rhs.rotation());
00096 }
00097 
00098 template <typename FloatType>
00099 typename Rigid2<FloatType>::Vector operator*(
00100     const Rigid2<FloatType>& rigid,
00101     const typename Rigid2<FloatType>::Vector& point) {
00102   return rigid.rotation() * point + rigid.translation();
00103 }
00104 
00105 // This is needed for gmock.
00106 template <typename T>
00107 std::ostream& operator<<(std::ostream& os,
00108                          const cartographer::transform::Rigid2<T>& rigid) {
00109   os << rigid.DebugString();
00110   return os;
00111 }
00112 
00113 using Rigid2d = Rigid2<double>;
00114 using Rigid2f = Rigid2<float>;
00115 
00116 template <typename FloatType>
00117 class Rigid3 {
00118  public:
00119   using Vector = Eigen::Matrix<FloatType, 3, 1>;
00120   using Quaternion = Eigen::Quaternion<FloatType>;
00121   using AngleAxis = Eigen::AngleAxis<FloatType>;
00122 
00123   Rigid3() : translation_(Vector::Zero()), rotation_(Quaternion::Identity()) {}
00124   Rigid3(const Vector& translation, const Quaternion& rotation)
00125       : translation_(translation), rotation_(rotation) {}
00126   Rigid3(const Vector& translation, const AngleAxis& rotation)
00127       : translation_(translation), rotation_(rotation) {}
00128 
00129   static Rigid3 Rotation(const AngleAxis& angle_axis) {
00130     return Rigid3(Vector::Zero(), Quaternion(angle_axis));
00131   }
00132 
00133   static Rigid3 Rotation(const Quaternion& rotation) {
00134     return Rigid3(Vector::Zero(), rotation);
00135   }
00136 
00137   static Rigid3 Translation(const Vector& vector) {
00138     return Rigid3(vector, Quaternion::Identity());
00139   }
00140 
00141   static Rigid3 FromArrays(const std::array<FloatType, 4>& rotation,
00142                            const std::array<FloatType, 3>& translation) {
00143     return Rigid3(Eigen::Map<const Vector>(translation.data()),
00144                   Eigen::Quaternion<FloatType>(rotation[0], rotation[1],
00145                                                rotation[2], rotation[3]));
00146   }
00147 
00148   static Rigid3<FloatType> Identity() { return Rigid3<FloatType>(); }
00149 
00150   template <typename OtherType>
00151   Rigid3<OtherType> cast() const {
00152     return Rigid3<OtherType>(translation_.template cast<OtherType>(),
00153                              rotation_.template cast<OtherType>());
00154   }
00155 
00156   const Vector& translation() const { return translation_; }
00157   const Quaternion& rotation() const { return rotation_; }
00158 
00159   Rigid3 inverse() const {
00160     const Quaternion rotation = rotation_.conjugate();
00161     const Vector translation = -(rotation * translation_);
00162     return Rigid3(translation, rotation);
00163   }
00164 
00165   std::string DebugString() const {
00166     return absl::Substitute("{ t: [$0, $1, $2], q: [$3, $4, $5, $6] }",
00167                             translation().x(), translation().y(),
00168                             translation().z(), rotation().w(), rotation().x(),
00169                             rotation().y(), rotation().z());
00170   }
00171 
00172   bool IsValid() const {
00173     return !std::isnan(translation_.x()) && !std::isnan(translation_.y()) &&
00174            !std::isnan(translation_.z()) &&
00175            std::abs(FloatType(1) - rotation_.norm()) < FloatType(1e-3);
00176   }
00177 
00178  private:
00179   Vector translation_;
00180   Quaternion rotation_;
00181 };
00182 
00183 template <typename FloatType>
00184 Rigid3<FloatType> operator*(const Rigid3<FloatType>& lhs,
00185                             const Rigid3<FloatType>& rhs) {
00186   return Rigid3<FloatType>(
00187       lhs.rotation() * rhs.translation() + lhs.translation(),
00188       (lhs.rotation() * rhs.rotation()).normalized());
00189 }
00190 
00191 template <typename FloatType>
00192 typename Rigid3<FloatType>::Vector operator*(
00193     const Rigid3<FloatType>& rigid,
00194     const typename Rigid3<FloatType>::Vector& point) {
00195   return rigid.rotation() * point + rigid.translation();
00196 }
00197 
00198 // This is needed for gmock.
00199 template <typename T>
00200 std::ostream& operator<<(std::ostream& os,
00201                          const cartographer::transform::Rigid3<T>& rigid) {
00202   os << rigid.DebugString();
00203   return os;
00204 }
00205 
00206 using Rigid3d = Rigid3<double>;
00207 using Rigid3f = Rigid3<float>;
00208 
00209 // Converts (roll, pitch, yaw) to a unit length quaternion. Based on the URDF
00210 // specification http://wiki.ros.org/urdf/XML/joint.
00211 Eigen::Quaterniond RollPitchYaw(double roll, double pitch, double yaw);
00212 
00213 // Returns an transform::Rigid3d given a 'dictionary' containing 'translation'
00214 // (x, y, z) and 'rotation' which can either we an array of (roll, pitch, yaw)
00215 // or a dictionary with (w, x, y, z) values as a quaternion.
00216 Rigid3d FromDictionary(common::LuaParameterDictionary* dictionary);
00217 
00218 }  // namespace transform
00219 }  // namespace cartographer
00220 
00221 #endif  // CARTOGRAPHER_TRANSFORM_RIGID_TRANSFORM_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35