rigid_transform.cc
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 #include "cartographer/transform/rigid_transform.h"
00018 
00019 #include <vector>
00020 
00021 #include "Eigen/Core"
00022 #include "Eigen/Geometry"
00023 #include "cartographer/common/lua_parameter_dictionary.h"
00024 #include "glog/logging.h"
00025 
00026 namespace cartographer {
00027 namespace transform {
00028 
00029 namespace {
00030 
00031 Eigen::Vector3d TranslationFromDictionary(
00032     common::LuaParameterDictionary* dictionary) {
00033   const std::vector<double> translation = dictionary->GetArrayValuesAsDoubles();
00034   CHECK_EQ(3, translation.size()) << "Need (x, y, z) for translation.";
00035   return Eigen::Vector3d(translation[0], translation[1], translation[2]);
00036 }
00037 
00038 }  // namespace
00039 
00040 Eigen::Quaterniond RollPitchYaw(const double roll, const double pitch,
00041                                 const double yaw) {
00042   const Eigen::AngleAxisd roll_angle(roll, Eigen::Vector3d::UnitX());
00043   const Eigen::AngleAxisd pitch_angle(pitch, Eigen::Vector3d::UnitY());
00044   const Eigen::AngleAxisd yaw_angle(yaw, Eigen::Vector3d::UnitZ());
00045   return yaw_angle * pitch_angle * roll_angle;
00046 }
00047 
00048 transform::Rigid3d FromDictionary(common::LuaParameterDictionary* dictionary) {
00049   const Eigen::Vector3d translation =
00050       TranslationFromDictionary(dictionary->GetDictionary("translation").get());
00051 
00052   auto rotation_dictionary = dictionary->GetDictionary("rotation");
00053   if (rotation_dictionary->HasKey("w")) {
00054     const Eigen::Quaterniond rotation(rotation_dictionary->GetDouble("w"),
00055                                       rotation_dictionary->GetDouble("x"),
00056                                       rotation_dictionary->GetDouble("y"),
00057                                       rotation_dictionary->GetDouble("z"));
00058     CHECK_NEAR(rotation.norm(), 1., 1e-9);
00059     return transform::Rigid3d(translation, rotation);
00060   } else {
00061     const std::vector<double> rotation =
00062         rotation_dictionary->GetArrayValuesAsDoubles();
00063     CHECK_EQ(3, rotation.size()) << "Need (roll, pitch, yaw) for rotation.";
00064     return transform::Rigid3d(
00065         translation, RollPitchYaw(rotation[0], rotation[1], rotation[2]));
00066   }
00067 }
00068 
00069 }  // namespace transform
00070 }  // namespace cartographer


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