Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef TOWR_VARIABLES_ANGULAR_STATE_CONVERTER_H_
00031 #define TOWR_VARIABLES_ANGULAR_STATE_CONVERTER_H_
00032
00033 #include <array>
00034
00035 #include <Eigen/Dense>
00036 #include <Eigen/Sparse>
00037
00038 #include "cartesian_dimensions.h"
00039 #include "node_spline.h"
00040
00041 namespace towr {
00042
00062 class EulerConverter {
00063 public:
00064 using Vector3d = Eigen::Vector3d;
00065 using EulerAngles = Vector3d;
00066 using EulerRates = Vector3d;
00067
00068 using JacobianRow = Eigen::SparseVector<double, Eigen::RowMajor>;
00069 using MatrixSXd = Eigen::SparseMatrix<double, Eigen::RowMajor>;
00070 using Jacobian = MatrixSXd;
00071 using JacRowMatrix = std::array<std::array<JacobianRow, k3D>, k3D>;
00072
00073 EulerConverter () = default;
00074
00090 EulerConverter (const NodeSpline::Ptr& euler_angles);
00091 virtual ~EulerConverter () = default;
00092
00098 Eigen::Quaterniond GetQuaternionBaseToWorld (double t) const;
00099
00105 MatrixSXd GetRotationMatrixBaseToWorld(double t) const;
00106
00112 Vector3d GetAngularVelocityInWorld(double t) const;
00113
00119 Vector3d GetAngularAccelerationInWorld(double t) const;
00120
00128 Jacobian GetDerivOfAngVelWrtEulerNodes(double t) const;
00129
00137 Jacobian GetDerivOfAngAccWrtEulerNodes(double t) const;
00138
00150 Jacobian DerivOfRotVecMult(double t, const Vector3d& v, bool inverse) const;
00151 private:
00152 NodeSpline::Ptr euler_;
00153
00154
00155
00156
00163 static MatrixSXd GetM(const EulerAngles& xyz);
00164
00168 static MatrixSXd GetMdot(const EulerAngles& xyz, const EulerRates& xyz_d);
00169
00178 Jacobian GetDerivMwrtNodes(double t, Dim3D dim) const;
00179
00185 Jacobian GetDerivMdotwrtNodes(double t, Dim3D dim) const;
00186
00192 JacRowMatrix GetDerivativeOfRotationMatrixWrtNodes(double t) const;
00193
00195 static MatrixSXd GetRotationMatrixBaseToWorld(const EulerAngles& xyz);
00196
00198 static Eigen::Quaterniond GetQuaternionBaseToWorld(const EulerAngles& pos);
00199
00201 static Vector3d GetAngularAccelerationInWorld(State euler);
00202
00204 static Vector3d GetAngularVelocityInWorld(const EulerAngles& pos,
00205 const EulerRates& vel);
00206
00207 JacobianRow GetJac(double t, Dx deriv, Dim3D dim) const;
00208 Jacobian jac_wrt_nodes_structure_;
00209 };
00210
00211 }
00212
00213 #endif