Go to the documentation of this file.00001 #ifndef __fovis_internal_utils_hpp__
00002 #define __fovis_internal_utils_hpp__
00003
00004 #include <stdio.h>
00005
00006 #include <Eigen/Core>
00007 #include <Eigen/Geometry>
00008 #include <emmintrin.h>
00009
00010 #include "options.hpp"
00011
00012 namespace fovis
00013 {
00014
00015 #define FOVIS_IS_ALIGNED16(x) (((uintptr_t)(x) & 0xf) == 0)
00016
00017 static inline int
00018 round_up_to_multiple(int x, int a)
00019 {
00020 int rem = x % a;
00021 if(rem)
00022 return x + (a - rem);
00023 return x;
00024 }
00025
00026 static inline Eigen::Vector3d
00027 _quat_to_roll_pitch_yaw(const Eigen::Quaterniond&q)
00028 {
00029 double roll_a = 2 * (q.w() * q.x() + q.y() * q.z());
00030 double roll_b = 1 - 2 * (q.x() * q.x() + q.y() * q.y());
00031 double roll = atan2(roll_a, roll_b);
00032
00033 double pitch_sin = 2 * (q.w() * q.y() - q.z() * q.x());
00034 double pitch = asin(pitch_sin);
00035
00036 double yaw_a = 2 * (q.w() * q.z() + q.x() * q.y());
00037 double yaw_b = 1 - 2 * (q.y() * q.y() + q.z() * q.z());
00038 double yaw = atan2(yaw_a, yaw_b);
00039 return Eigen::Vector3d(roll, pitch, yaw);
00040 }
00041
00042 static inline Eigen::Quaterniond
00043 _rpy_to_quat(const Eigen::Vector3d rpy)
00044 {
00045 double roll = rpy(0), pitch = rpy(1), yaw = rpy(2);
00046
00047 double halfroll = roll / 2;
00048 double halfpitch = pitch / 2;
00049 double halfyaw = yaw / 2;
00050
00051 double sin_r2 = sin(halfroll);
00052 double sin_p2 = sin(halfpitch);
00053 double sin_y2 = sin(halfyaw);
00054
00055 double cos_r2 = cos(halfroll);
00056 double cos_p2 = cos(halfpitch);
00057 double cos_y2 = cos(halfyaw);
00058
00059 Eigen::Quaterniond q;
00060 q.w() = cos_r2 * cos_p2 * cos_y2 + sin_r2 * sin_p2 * sin_y2;
00061 q.x() = sin_r2 * cos_p2 * cos_y2 - cos_r2 * sin_p2 * sin_y2;
00062 q.y() = cos_r2 * sin_p2 * cos_y2 + sin_r2 * cos_p2 * sin_y2;
00063 q.z() = cos_r2 * cos_p2 * sin_y2 - sin_r2 * sin_p2 * cos_y2;
00064 return q;
00065 }
00066
00067 static inline void
00068 print_isometry(const Eigen::Isometry3d & iso)
00069 {
00070 const Eigen::Vector3d & t = iso.translation();
00071 Eigen::Vector3d rpy = _quat_to_roll_pitch_yaw(Eigen::Quaterniond(iso.rotation()))*180.0/M_PI;
00072 fprintf(stderr, "trans:(% 6.3f % 6.3f % 6.3f) rot:(% 6.3f % 6.3f % 6.3f)",t(0),t(1),t(2),rpy(0),rpy(1),rpy(2));
00073
00074 }
00075
00076 bool optionsGetInt(const VisualOdometryOptions& options, std::string name,
00077 int* result);
00078
00079 bool optionsGetBool(const VisualOdometryOptions& options, std::string name,
00080 bool* result);
00081
00082 int optionsGetIntOrFromDefault(const VisualOdometryOptions& options,
00083 std::string name, const VisualOdometryOptions& defaults);
00084
00085 bool optionsGetBoolOrFromDefault(const VisualOdometryOptions& options,
00086 std::string name, const VisualOdometryOptions& defaults);
00087
00088 bool optionsGetDouble(const VisualOdometryOptions& options, std::string name,
00089 double* result);
00090
00091 double optionsGetDoubleOrFromDefault(const VisualOdometryOptions& options,
00092 std::string name, const VisualOdometryOptions& defaults);
00093
00094 }
00095
00096 #endif