38 Eigen::VectorXd
VectorTransform(
double px,
double py,
double pz,
double qx,
double qy,
double qz,
double qw)
40 Eigen::VectorXd ret((Eigen::VectorXd(7) << px, py, pz, qx, qy, qz, qw).finished());
58 double norm = val.tail(4).norm();
59 if (norm <= 0.0)
ThrowPretty(
"Invalid quaternion!");
60 return KDL::Frame(KDL::Rotation::Quaternion(val(3) / norm, val(4) / norm, val(5) / norm, val(6) / norm), KDL::Vector(val(0), val(1), val(2)));
63 return KDL::Frame(KDL::Rotation::RPY(val(3), val(4), val(5)), KDL::Vector(val(0), val(1), val(2)));
65 return KDL::Frame(KDL::Vector(val(0), val(1), val(2)));
67 ThrowPretty(
"Eigen vector has incorrect length! (" + std::to_string(val.rows()) +
")");
82 return KDL::Frame(KDL::Rotation(val(0, 0), val(0, 1), val(0, 2), val(1, 0), val(1, 1), val(1, 2), val(2, 0), val(2, 1), val(2, 2)), KDL::Vector(val(0, 3), val(1, 3), val(2, 3)));
84 ThrowPretty(
"Eigen matrix has incorrect number of rows! (" + std::to_string(val.rows()) +
")");
87 ThrowPretty(
"Eigen matrix has incorrect number of columns! (" + std::to_string(val.cols()) +
")");
91 Eigen::MatrixXd
GetFrame(
const KDL::Frame& val)
93 Eigen::Isometry3d ret;
101 Eigen::VectorXd ret(3 + rotation_length);
105 ret.segment(3, rotation_length) =
SetRotation(val.M, type);
119 if (data.sum() == 0.0)
ThrowPretty(
"Invalid quaternion transform!");
120 return KDL::Rotation::Quaternion(data(0), data(1), data(2), data(3));
122 return KDL::Rotation::RPY(data(0), data(1), data(2));
124 return KDL::Rotation::EulerZYX(data(0), data(1), data(2));
126 return KDL::Rotation::EulerZYZ(data(0), data(1), data(2));
129 KDL::Vector axis(data(0), data(1), data(2));
130 double angle = axis.Norm();
131 if (fabs(
angle) > 1e-10)
133 return KDL::Rotation::Rot(axis,
angle);
137 return KDL::Rotation();
141 if (data.sum() == 0.0)
ThrowPretty(
"Invalid matrix transform!");
142 return KDL::Rotation(data(0), data(1), data(2),
143 data(3), data(4), data(5),
144 data(6), data(7), data(8));
146 ThrowPretty(
"Unknown rotation representation type!");
156 ret = Eigen::Quaterniond(Eigen::Map<const Eigen::Matrix3d>(data.data).transpose()).coeffs();
160 data.GetRPY(ret(0), ret(1), ret(2));
164 data.GetEulerZYX(ret(0), ret(1), ret(2));
168 data.GetEulerZYZ(ret(0), ret(1), ret(2));
171 ret = Eigen::Map<const Eigen::Vector3d>(data.GetRot().data);
174 ret = Eigen::Map<const Eigen::VectorXd>(data.data, 9);
177 ThrowPretty(
"Unknown rotation representation type!");