22 #include "Eigen/Geometry" 24 #include "glog/logging.h" 31 Eigen::Vector3d TranslationFromDictionary(
34 CHECK_EQ(3, translation.size()) <<
"Need (x, y, z) for translation.";
35 return Eigen::Vector3d(translation[0], translation[1], translation[2]);
40 Eigen::Quaterniond
RollPitchYaw(
const double roll,
const double pitch,
42 const Eigen::AngleAxisd roll_angle(roll, Eigen::Vector3d::UnitX());
43 const Eigen::AngleAxisd pitch_angle(pitch, Eigen::Vector3d::UnitY());
44 const Eigen::AngleAxisd yaw_angle(yaw, Eigen::Vector3d::UnitZ());
45 return yaw_angle * pitch_angle * roll_angle;
49 const Eigen::Vector3d translation =
50 TranslationFromDictionary(dictionary->
GetDictionary(
"translation").get());
52 auto rotation_dictionary = dictionary->
GetDictionary(
"rotation");
53 if (rotation_dictionary->HasKey(
"w")) {
54 const Eigen::Quaterniond rotation(rotation_dictionary->GetDouble(
"w"),
55 rotation_dictionary->GetDouble(
"x"),
56 rotation_dictionary->GetDouble(
"y"),
57 rotation_dictionary->GetDouble(
"z"));
58 CHECK_NEAR(rotation.norm(), 1., 1e-9);
61 const std::vector<double> rotation =
62 rotation_dictionary->GetArrayValuesAsDoubles();
63 CHECK_EQ(3, rotation.size()) <<
"Need (roll, pitch, yaw) for rotation.";
65 translation,
RollPitchYaw(rotation[0], rotation[1], rotation[2]));
std::vector< double > GetArrayValuesAsDoubles()
std::unique_ptr< LuaParameterDictionary > GetDictionary(const string &key)