47 #ifndef _MIRA_RIGID_TRANSFORM_H_ 48 #define _MIRA_RIGID_TRANSFORM_H_ 73 typename TransformDerived,
74 typename OtherDerived,
75 int OtherRows=OtherDerived::RowsAtCompileTime,
76 int OtherCols=OtherDerived::ColsAtCompileTime>
77 struct ei_rigidtransform_product_impl
79 static_assert(D!=D,
"You are trying to apply a rigid transform to a matrix " 100 template <
typename T,
int D>
103 static_assert(D!=D,
"RigidTransform is not defined for this dimension. " 104 "Only 2 and 3 dimensions are available.");
127 template <
typename T,
int D>
130 static_assert(D!=D,
"RigidTransformCov is not defined for this dimension. " 131 "Only 2 and 3 dimensions are available.");
140 template <
typename T,
int D,
typename TRotation,
typename TransformDerived>
173 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
176 t(translation),
r(rotation) {}
185 return TransformDerived(inv.RotationType::operator*(-
t), inv);
194 T prec = std::numeric_limits<T>::epsilon())
const 196 return t.isApprox(other.
t,prec) &&
r.isApprox(other.
r, prec);
224 template <
typename OtherDerived>
225 typename ei_rigidtransform_product_impl<D, TransformDerived, OtherDerived>::TResult
228 return ei_rigidtransform_product_impl<D, TransformDerived, OtherDerived>::run(*
this, other.derived());
255 m.template block<Dim,Dim>(0,0) =
r.toRotationMatrix();
256 m.template block<Dim,1>(0,
Dim) =
t.transpose();
263 TransformDerived*
This() {
return static_cast<TransformDerived*
>(
this); }
265 const TransformDerived*
This()
const {
266 return static_cast<const TransformDerived*
>(
this);
276 return TransformDerived(a.
r * b.
t + a.
t,
r);
296 template <
typename T>
298 Eigen::Rotation2D<T>, RigidTransform<T,2> >
313 Base(translation,rotation) {}
320 Base(translation,
Eigen::Rotation2D<T>(angle)) {}
328 Eigen::Rotation2D<T>(angle)) {}
335 template <
typename UnitTag,
typename Derived>
338 Eigen::Rotation2D<T>(angle.rad())) {}
343 template <
typename U>
346 this->r.template cast<U>());
352 T&
x() {
return this->t.x(); }
354 T
x()
const {
return this->t.x(); }
357 T&
y() {
return this->t.y(); }
359 T
y()
const {
return this->t.y(); }
362 T&
phi() {
return this->r.angle(); }
364 T
phi()
const {
return this->r.angle(); }
368 template <
typename Reflector>
371 m.property(
"X", this->t[0],
"The translational part of the transform");
372 m.property(
"Y", this->t[1],
"The translational part of the transform");
373 m.property(
"Phi", getter<T>(rad2deg<T>, this->r.angle()),
374 setter<T>(deg2rad<T>, this->r.angle()),
375 "The orientation in degrees");
380 os <<
"t: " << tf.t.transpose() <<
"\n";
381 os <<
"r: " << tf.r.angle() <<
"\n";
403 template <
typename T>
411 static const int CovarianceDim = 3;
423 return CovMatrixType::Zero();
445 Base(translation,rotation), cov(covariance) {}
453 Base(translation,
Eigen::Rotation2D<T>(angle)),
462 Eigen::Rotation2D<T>(angle)), cov(covariance) {}
469 template <
typename UnitTag,
typename Derived>
473 Eigen::Rotation2D<T>(angle.rad())), cov(covariance) {}
483 Eigen::Rotation2D<T>(angle)),
484 cov(
Eigen::DiagonalMatrix<T,3>(covX, covY, covAngle)) {}
491 template <
typename UnitTag,
typename Derived>
493 T covX, T covY, T covAngle) :
495 Eigen::Rotation2D<T>(angle.rad())),
496 cov(
Eigen::DiagonalMatrix<T,3>(covX, covY, covAngle)) {}
501 template <
typename U>
504 this->r.template cast<U>(),
505 this->cov.template cast<U>());
510 template <
typename Reflector>
514 r.member(
"Cov", cov,
"The covariance matrix (using radians for phi)");
519 os <<
"t: " << tf.t.transpose() <<
"\n";
520 os <<
"r: " << tf.r.angle() <<
"\n";
521 os <<
"cov:\n" << tf.cov <<
"\n";
535 T sinr = std::sin(this->r.angle());
536 T cosr = std::cos(this->r.angle());
539 J << -cosr, -sinr, this->t(0)*sinr -this->t(1)*cosr,
540 sinr, -cosr, this->t(0)*cosr +this->t(1)*sinr,
549 propagateCov(cov,*
this,other);
550 Base::operator*=(other);
556 propagateCov(cov,*
this,other);
557 Base::operator*=(other);
565 propagateCov(t.cov,a,b);
573 propagateCov(t.cov,a,b);
581 propagateCov(t.cov,a,b);
594 static void propagateCov(CovMatrixType& C,
const Base& a,
611 template <
typename T>
613 Eigen::Quaternion<T>, RigidTransform<T,3> >
620 Base(
Eigen::Matrix<T,3,1>(0,0,0),
Eigen::Quaternion<T>::Identity()) {}
624 Base(translation,rotation) {}
633 template <
typename U>
636 this->r.template cast<U>());
642 T&
x() {
return this->t.x(); }
644 T
x()
const {
return this->t.x(); }
647 T&
y() {
return this->t.y(); }
649 T
y()
const {
return this->t.y(); }
652 T&
z() {
return this->t.z(); }
654 T
z()
const {
return this->t.z(); }
683 template <
typename Derived>
686 r.
property(
"X", this->t[0],
"The translational part of the transform");
687 r.
property(
"Y", this->t[1],
"The translational part of the transform");
688 r.
property(
"Z", this->t[2],
"The translational part of the transform");
690 r.
member(
"Rotation", this->r.coeffs(),
"The rotational part");
693 template <
typename Derived>
696 r.
property(
"X", this->t[0],
"The translational part of the transform");
697 r.
property(
"Y", this->t[1],
"The translational part of the transform");
698 r.
property(
"Z", this->t[2],
"The translational part of the transform");
700 r.
member(
"Rotation", this->r.coeffs(),
"The rotational part");
703 template <
typename Reflector>
706 r.property(
"X", this->t[0],
"The translational part of the transform");
707 r.property(
"Y", this->t[1],
"The translational part of the transform");
708 r.property(
"Z", this->t[2],
"The translational part of the transform");
711 T yaw =
rad2deg(ypr.template get<0>());
712 T pitch =
rad2deg(ypr.template get<1>());
713 T roll =
rad2deg(ypr.template get<2>());
714 r.member(
"Yaw" , yaw,
"The yaw angle (phi, in degrees)");
715 r.member(
"Pitch", pitch,
"The pitch angle (theta, in degrees)");
716 r.member(
"Roll" , roll,
"The roll angle (psi, in degrees)");
719 template <
typename Reflector>
723 r.property(
"X", this->t[0],
"The translational part of the transform");
724 r.property(
"Y", this->t[1],
"The translational part of the transform");
725 r.property(
"Z", this->t[2],
"The translational part of the transform");
726 r.member(
"Yaw" , yaw,
"The yaw angle (phi, in degrees)");
727 r.member(
"Pitch", pitch,
"The pitch angle (theta, in degrees)");
728 r.member(
"Roll" , roll,
"The roll angle (psi, in degrees)");
736 os <<
"t: " << tf.t.transpose() <<
"\n";
737 os <<
"r: " << tf.r.w() <<
" " << tf.r.x() <<
" " << tf.r.y() <<
" " << tf.r.z() <<
"\n";
762 template <
typename T>
769 static const int CovarianceDim = 7;
772 static const int EulerCovarianceDim = 6;
792 return CovMatrixType::Zero();
800 return YawPitchRollCovMatrixType::Zero();
821 Base(translation,rotation), cov(covariance) {}
830 Base(translation, rotation),
849 template <
typename U>
853 this->r.template cast<U>(),
854 CovMatrixTypeU(this->cov.template cast<U>()));
869 template <
typename Derived>
872 r.
property(
"X", this->t[0],
"The translational part of the transform");
873 r.
property(
"Y", this->t[1],
"The translational part of the transform");
874 r.
property(
"Z", this->t[2],
"The translational part of the transform");
876 r.
member(
"Rotation", this->r.coeffs(),
"The rotational part");
878 r.
member(
"Cov", cov,
"The covariance matrix");
881 template <
typename Derived>
884 r.
property(
"X", this->t[0],
"The translational part of the transform");
885 r.
property(
"Y", this->t[1],
"The translational part of the transform");
886 r.
property(
"Z", this->t[2],
"The translational part of the transform");
888 r.
member(
"Rotation", this->r.coeffs(),
"The rotational part");
890 r.
member(
"Cov", cov,
"The covariance matrix");
893 template <
typename Reflector>
896 r.property(
"X", this->t[0],
"The translational part of the transform");
897 r.property(
"Y", this->t[1],
"The translational part of the transform");
898 r.property(
"Z", this->t[2],
"The translational part of the transform");
901 T yaw =
rad2deg(ypr.template get<0>());
902 T pitch =
rad2deg(ypr.template get<1>());
903 T roll =
rad2deg(ypr.template get<2>());
904 r.member(
"Yaw" , yaw,
"The yaw angle (phi, in degrees)");
905 r.member(
"Pitch", pitch,
"The pitch angle (theta, in degrees)");
906 r.member(
"Roll" , roll,
"The roll angle (psi, in degrees)");
910 r.member(
"Cov", yprcov,
"The covariance matrix for [x,y,z,qw,qx,qy,qz]");
913 template <
typename Reflector>
917 r.property(
"X", this->t[0],
"The translational part of the transform");
918 r.property(
"Y", this->t[1],
"The translational part of the transform");
919 r.property(
"Z", this->t[2],
"The translational part of the transform");
920 r.member(
"Yaw" , yaw,
"The yaw angle (phi, in degrees)");
921 r.member(
"Pitch", pitch,
"The pitch angle (theta, in degrees)");
922 r.member(
"Roll" , roll,
"The roll angle (psi, in degrees)");
930 r.member(
"Cov", yprcov,
"The covariance matrix for [x,y,z,qw,qx,qy,qz]");
940 os <<
"t: " << tf.t.transpose() <<
"\n";
941 os <<
"r: " << tf.r.w() <<
" " << tf.r.x() <<
" " << tf.r.y() <<
" " << tf.r.z() <<
"\n";
942 os <<
"cov:\n" << tf.cov <<
"\n";
958 J.template block<3,3>(0,0) <<
959 (T)2.0 * (this->r.y() * this->r.y() + this->r.z() * this->r.z()) - (T)1.0,
960 -(T)2.0 * (this->r.w() * this->r.z() + this->r.x() * this->r.y()) ,
961 (T)2.0 * (this->r.w() * this->r.y() - this->r.x() * this->r.z()) ,
963 (T)2.0 * (this->r.w() * this->r.z() - this->r.x() * this->r.y()) ,
964 (T)2.0 * (this->r.x() * this->r.x() + this->r.z() * this->r.z()) - (T)1.0,
965 -(T)2.0 * (this->r.w() * this->r.x() + this->r.y() * this->r.z()) ,
967 -(T)2.0 * (this->r.w() * this->r.y() + this->r.x() * this->r.z()) ,
968 (T)2.0 * (this->r.w() * this->r.x() - this->r.y() * this->r.z()) ,
969 (T)2.0 * (this->r.x() * this->r.x() + this->r.y() * this->r.y()) - (T)1.0;
973 J.template block<3,4>(0,3) <<
974 -(T)2.0 * (this->r.z() * this->t(1) - this->r.y() * this->t(2) ),
975 -(T)2.0 * (this->r.y() * this->t(1) + this->r.z() * this->t(2) ),
976 -(T)2.0 * (this->r.x() * this->t(1) - (T)2.0 * this->r.y() * this->t(0) - this->r.w() * this->t(2)),
977 -(T)2.0 * (this->r.x() * this->t(2) + this->r.w() * this->t(1) - (T)2.0 * this->r.z() * this->t(0)),
979 -(T)2.0 * (this->r.x() * this->t(2) - this->r.z() * this->t(0) ),
980 -(T)2.0 * (this->r.y() * this->t(0) - (T)2.0 * this->r.x() * this->t(1) + this->r.w() * this->t(2)),
981 -(T)2.0 * (this->r.x() * this->t(0) + this->r.z() * this->t(2) ),
982 -(T)2.0 * (this->r.y() * this->t(2) - (T)2.0 * this->r.z() * this->t(1) - this->r.w() * this->t(0)),
984 -(T)2.0 * (this->r.y() * this->t(0) - this->r.x() * this->t(1) ),
985 -(T)2.0 * (this->r.z() * this->t(0) - this->r.w() * this->t(1) - (T)2.0 * this->r.x() * this->t(2)),
986 -(T)2.0 * (this->r.z() * this->t(1) + this->r.w() * this->t(0) - (T)2.0 * this->r.y() * this->t(2)),
987 -(T)2.0 * (this->r.x() * this->t(0) + this->r.y() * this->t(1) );
995 propagateCov(cov,*
this,other);
996 Base::operator*=(other);
1002 propagateCov(cov,*
this,other);
1003 Base::operator*=(other);
1011 propagateCov(t.cov,a,b);
1019 propagateCov(t.cov,a,b);
1027 propagateCov(t.cov,a,b);
1034 static void propagateCov(CovMatrixType& oC,
1037 static void propagateCov(CovMatrixType& oC,
1040 static void propagateCov(CovMatrixType& C,
1110 template <
typename T>
1121 T sinrw = std::sin(w.r.angle());
1122 T cosrw = std::cos(w.r.angle());
1125 Ja << cosrw, -sinrw, 0,
1129 Jw << 1, 0, -a.t(0)*sinrw -a.t(1)*cosrw,
1130 0, 1, a.t(0)*cosrw -a.t(1)*sinrw,
1134 oC = Ja * a.cov * Ja.transpose() + Jw * w.cov * Jw.transpose();
1138 template <
typename T>
1139 inline void RigidTransformCov<T,2>::propagateCov(CovMatrixType& oC,
1140 const RigidTransformCov& w,
1149 T sinrw = std::sin(w.r.angle());
1150 T cosrw = std::cos(w.r.angle());
1153 Jw << 1, 0, -a.t(0)*sinrw -a.t(1)*cosrw,
1154 0, 1, a.t(0)*cosrw -a.t(1)*sinrw,
1158 oC = Jw * w.cov * Jw.transpose();
1161 template <
typename T>
1162 inline void RigidTransformCov<T,2>::propagateCov(CovMatrixType& oC,
1164 const RigidTransformCov& a)
1172 T sinrw = std::sin(w.r.angle());
1173 T cosrw = std::cos(w.r.angle());
1176 Ja << cosrw, -sinrw, 0,
1181 oC = Ja * a.cov * Ja.transpose();
1194 template <
typename T>
1195 inline void RigidTransformCov<T,3>::propagateCov(CovMatrixType& oC,
1196 const RigidTransformCov& w,
1197 const RigidTransformCov& a)
1202 CovMatrixType Jw = CovMatrixType::Identity();
1204 Jw.template block<3,4>(0,3) <<
1205 - w.r.z()*a.t(1,0)+ w.r.y()*a.t(2,0),
1206 w.r.y()*a.t(1,0)+ w.r.z()*a.t(2,0),
1207 -(T)2.0*w.r.y()*a.t(0,0)+ w.r.x()*a.t(1,0)+ w.r.w()*a.t(2,0),
1208 -(T)2.0*w.r.z()*a.t(0,0)- w.r.w()*a.t(1,0)+ w.r.x()*a.t(2,0),
1210 w.r.z()*a.t(0,0) - w.r.x()*a.t(2,0),
1211 w.r.y()*a.t(0,0)-(T)2.0*w.r.x()*a.t(1,0)- w.r.w()*a.t(2,0),
1212 w.r.x()*a.t(0,0) + w.r.z()*a.t(2,0),
1213 w.r.w()*a.t(0,0)-(T)2.0*w.r.z()*a.t(1,0)+ w.r.y()*a.t(2,0),
1215 -w.r.y()*a.t(0,0)+ w.r.x()*a.t(1,0) ,
1216 w.r.z()*a.t(0,0)+ w.r.w()*a.t(1,0)-(T)2.0*w.r.x()*a.t(2,0),
1217 -w.r.w()*a.t(0,0)+ w.r.z()*a.t(1,0)-(T)2.0*w.r.y()*a.t(2,0),
1218 w.r.x()*a.t(0,0)+ w.r.y()*a.t(1,0);
1219 Jw.template block<3,4>(0,3) *= (T)2.0;
1221 Jw.template block<4,4>(3,3) <<
1222 a.r.w(),-a.r.x(),-a.r.y(),-a.r.z(),
1223 a.r.x(), a.r.w(), a.r.z(),-a.r.y(),
1224 a.r.y(),-a.r.z(), a.r.w(), a.r.x(),
1225 a.r.z(), a.r.y(),-a.r.x(), a.r.w();
1227 CovMatrixType Ja = CovMatrixType::Identity();
1229 Ja.template block<3,3>(0,0) <<
1230 (T)0.5-w.r.y()*w.r.y()-w.r.z()*w.r.z(),
1231 w.r.x()*w.r.y()-w.r.w()*w.r.z(),
1232 w.r.w()*w.r.y()+w.r.x()*w.r.z(),
1234 w.r.w()*w.r.z()+w.r.x()*w.r.y(),
1235 (T)0.5-w.r.x()*w.r.x()-w.r.z()*w.r.z(),
1236 w.r.y()*w.r.z()-w.r.w()*w.r.x(),
1238 w.r.x()*w.r.z()-w.r.w()*w.r.y(),
1239 w.r.w()*w.r.x()+w.r.y()*w.r.z(),
1240 (T)0.5-w.r.x()*w.r.x()-w.r.y()*w.r.y();
1241 Ja.template block<3,3>(0,0) *= (T)2.0;
1243 Ja.template block<4,4>(3,3) <<
1244 w.r.w(), -w.r.x(), -w.r.y(), -w.r.z(),
1245 w.r.x(), w.r.w(), -w.r.z(), w.r.y(),
1246 w.r.y(), w.r.z(), w.r.w(), -w.r.x(),
1247 w.r.z(), -w.r.y(), w.r.x(), w.r.w();
1250 oC = Jw * w.cov * Jw.transpose() + Ja * a.cov * Ja.transpose();
1253 template <
typename T>
1254 inline void RigidTransformCov<T,3>::propagateCov(CovMatrixType& oC,
1255 const RigidTransformCov& w,
1261 CovMatrixType Jw = CovMatrixType::Identity();
1263 Jw.template block<3,4>(0,3) <<
1264 - w.r.z()*a.t(1,0)+ w.r.y()*a.t(2,0),
1265 w.r.y()*a.t(1,0)+ w.r.z()*a.t(2,0),
1266 -(T)2.0*w.r.y()*a.t(0,0)+ w.r.x()*a.t(1,0)+ w.r.w()*a.t(2,0),
1267 -(T)2.0*w.r.z()*a.t(0,0)- w.r.w()*a.t(1,0)+ w.r.x()*a.t(2,0),
1269 w.r.z()*a.t(0,0) - w.r.x()*a.t(2,0),
1270 w.r.y()*a.t(0,0)-(T)2.0*w.r.x()*a.t(1,0)- w.r.w()*a.t(2,0),
1271 w.r.x()*a.t(0,0) + w.r.z()*a.t(2,0),
1272 w.r.w()*a.t(0,0)-(T)2.0*w.r.z()*a.t(1,0)+ w.r.y()*a.t(2,0),
1274 -w.r.y()*a.t(0,0)+ w.r.x()*a.t(1,0) ,
1275 w.r.z()*a.t(0,0)+ w.r.w()*a.t(1,0)-2.0*w.r.x()*a.t(2,0),
1276 -w.r.w()*a.t(0,0)+ w.r.z()*a.t(1,0)-2.0*w.r.y()*a.t(2,0),
1277 w.r.x()*a.t(0,0)+ w.r.y()*a.t(1,0);
1278 Jw.template block<3,4>(0,3) *= (T)2.0;
1280 Jw.template block<4,4>(3,3) <<
1281 a.r.w(),-a.r.x(),-a.r.y(),-a.r.z(),
1282 a.r.x(), a.r.w(), a.r.z(),-a.r.y(),
1283 a.r.y(),-a.r.z(), a.r.w(), a.r.x(),
1284 a.r.z(), a.r.y(),-a.r.x(), a.r.w();
1287 oC = Jw * w.cov * Jw.transpose();
1290 template <
typename T>
1291 inline void RigidTransformCov<T,3>::propagateCov(CovMatrixType& oC,
1293 const RigidTransformCov& a)
1298 CovMatrixType Ja = CovMatrixType::Identity();
1300 Ja.template block<3,3>(0,0) <<
1301 (T)0.5-w.r.y()*w.r.y()-w.r.z()*w.r.z(),
1302 w.r.x()*w.r.y()-w.r.w()*w.r.z(),
1303 w.r.w()*w.r.y()+w.r.x()*w.r.z(),
1305 w.r.w()*w.r.z()+w.r.x()*w.r.y(),
1306 (T)0.5-w.r.x()*w.r.x()-w.r.z()*w.r.z(),
1307 w.r.y()*w.r.z()-w.r.w()*w.r.x(),
1309 w.r.x()*w.r.z()-w.r.w()*w.r.y(),
1310 w.r.w()*w.r.x()+w.r.y()*w.r.z(),
1311 (T)0.5-w.r.x()*w.r.x()-w.r.y()*w.r.y();
1312 Ja.template block<3,3>(0,0) *= (T)2.0;
1314 Ja.template block<4,4>(3,3) <<
1315 w.r.w(), -w.r.x(), -w.r.y(), -w.r.z(),
1316 w.r.x(), w.r.w(), -w.r.z(), w.r.y(),
1317 w.r.y(), w.r.z(), w.r.w(), -w.r.x(),
1318 w.r.z(), -w.r.y(), w.r.x(), w.r.w();
1321 oC = Ja * a.cov * Ja.transpose();
1336 template <
typename T,
int D,
typename S>
1342 lerp(t1.r, t2.r, alpha));
1354 template <
typename T,
int D,
typename S>
1360 lerp(t1.r, t2.r, alpha),
1361 lerp(t1.cov, t2.cov, alpha));
1377 template<
typename T,
int D>
1380 const auto transformMatrix = p.getMatrix();
1382 for (
int i = 0; i < matrixDim; ++i) {
1383 for (
int j = 0; j < matrixDim; ++j) {
1384 if (boost::math::isnan(transformMatrix(i,j))) {
1402 template<
typename T,
int D>
1406 if (!transformValid) {
1410 constexpr
auto precision = Eigen::NumTraits<T>::dummy_precision();
1414 for (
int i = 0; i < covDim; ++i) {
1415 for (
int j = 0; j < covDim; ++j) {
1416 if (boost::math::isnan(p.cov(i, j))) {
1423 for (
int i = 0; i < covDim; ++i) {
1424 for (
int j = i + 1; j < covDim; ++j) {
1425 const bool almostEqual = std::abs(p.cov(i, j) - p.cov(j, i)) <=
precision;
1434 const auto covValid = ldlt.info() != Eigen::NumericalIssue && ldlt.isPositive();
1442 template<
int D,
typename TransformDerived,
typename OtherDerived>
1443 struct ei_rigidtransform_product_impl<D, TransformDerived, OtherDerived,D, 1>
1445 typedef typename OtherDerived::Scalar Scalar;
1446 typedef RigidTransformBase<Scalar, D, typename TransformDerived::RotationType, TransformDerived> TTransform;
1450 static TResult run(
const TTransform& t,
const OtherDerived& v)
1457 template<
int D,
typename TransformDerived,
typename OtherDerived>
1458 struct ei_rigidtransform_product_impl<D, TransformDerived, OtherDerived,
Eigen::Dynamic, Eigen::Dynamic>
1460 typedef typename OtherDerived::Scalar Scalar;
1461 typedef RigidTransformBase<Scalar, D, typename TransformDerived::RotationType, TransformDerived> TTransform;
1465 static TResult run(
const TTransform& t,
const OtherDerived& v)
INTERNAL std::enable_if< std::is_floating_point< T >::value, T >::type deg2rad(T value)
Convert degree to radian, for floating point arguments (return type = argument type) ...
Definition: Angle.h:82
Typedefs for OS independent basic data types.
Eigen::Matrix< T, 6, 6 > quaternionCovToYawPitchRollCov(const Eigen::Matrix< T, 7, 7 > &covariance, const Eigen::Quaternion< T > &q)
Converts a 7x7 dimensional quaternion covariance (3D + Quaternion) back to a 6x6 dimensional euler co...
Definition: YawPitchRoll.h:318
Include file for all eigen related things.
boost::tuples::tuple< T, T, T > quaternionToYawPitchRoll(const Eigen::Quaternion< T > &q)
Converts a quaternion back to yaw, pitch, roll angles.
Definition: YawPitchRoll.h:299
specialize cv::DataType for our ImgPixel and inherit from cv::DataType<Vec>
Definition: IOService.h:67
void member(const char *name, T &member, const char *comment, ReflectCtrlFlags flags=REFLECT_CTRLFLAG_NONE)
Definition: RecursiveMemberReflector.h:862
void quaternionCovFromYawPitchRollCov(const Eigen::Matrix< T, 6, 6 > &eulerCovariance, float yaw, float pitch, float roll, Eigen::Quaternion< T > &oOrientation, Eigen::Matrix< T, 7, 7 > &oCovariance)
Converts 6x6 dimensional covariance matrix (3D + yaw, pitch and roll) angles to a 7x7 dimensional qua...
Definition: YawPitchRoll.h:201
#define MIRA_SPLIT_REFLECT_MEMBER
Macro that insert a class member reflect() method just splitting reflection into a reflectRead() and ...
Definition: SplitReflect.h:209
#define MIRA_REFLECT_BASE(reflector, BaseClass)
Macro that can be used to reflect the base class easily.
Definition: ReflectorInterface.h:912
Definition: YawPitchRoll.h:684
Quaternion inverse(void) const
bool isWellDefined(const RigidTransform< T, D > &p)
Checks whether a RigidTransform is valid.
Definition: RigidTransform.h:1378
T lerp(const T &a, const T &b, S alpha)
Linear interpolation of different types like scalars, angles and rotations, vectors, etc.
Definition: Lerp.h:76
Rotation2D inverse() const
void property(const char *name, T &member, const char *comment, PropertyHint &&hint=PropertyHint(), ReflectCtrlFlags flags=REFLECT_CTRLFLAG_NONE)
Definition: RecursiveMemberReflector.h:964
Functions for linear interpolation of different types like scalars, angles and rotations.
Conversion from yaw, pitch and roll to Quaternion and vice versa.
Deserializer that uses BinaryIstream to deserialize the objects from binary format.
Definition: BinarySerializer.h:928
By default, IsCheapToCopy<T>::value evaluates to true for fundamental types T, false for all other ty...
Definition: IsCheapToCopy.h:63
Type trait to define if a class is cheap to copy.
Implementations of angles (values in periodic interval of width 2*pi) with arbitrary base type...
Eigen::Matrix< typename Eigen::MatrixBase< Derived >::Scalar, 3, 1 > eulerAngles(const Eigen::MatrixBase< Derived > &mat, typename Eigen::MatrixBase< Derived >::Index a0, typename Eigen::MatrixBase< Derived >::Index a1, typename Eigen::MatrixBase< Derived >::Index a2)
Returns the Euler-angles of the rotation matrix mat using the convention defined by the triplet (a0...
Definition: YawPitchRoll.h:86
Definition: BinarySerializer.h:257
PropertyHint precision(int p)
Sets the attribute "precision".
Definition: PropertyHint.h:285
std::enable_if< std::is_floating_point< T >::value, T >::type rad2deg(T value)
Convert radian to degree, for floating point arguments (return type = argument type) ...
Definition: Angle.h:106
Eigen::Quaternion< T > quaternionFromYawPitchRoll(T yaw, T pitch, T roll)
Converts yaw, pitch and roll angles to a quaternion.
Definition: YawPitchRoll.h:156
Provides definition for getters and setters that are used with the serialization framework.
Base class template for derived Angle implementations.
Definition: Angle.h:183