30 #ifndef TOWR_VARIABLES_ANGULAR_STATE_CONVERTER_H_ 31 #define TOWR_VARIABLES_ANGULAR_STATE_CONVERTER_H_ 35 #include <Eigen/Dense> 36 #include <Eigen/Sparse> 68 using JacobianRow = Eigen::SparseVector<double, Eigen::RowMajor>;
69 using MatrixSXd = Eigen::SparseMatrix<double, Eigen::RowMajor>;
virtual ~EulerConverter()=default
Stores at state comprised of values and higher-order derivatives.
std::shared_ptr< NodeSpline > Ptr
JacRowMatrix GetDerivativeOfRotationMatrixWrtNodes(double t) const
matrix of derivatives of each cell w.r.t node values.
Jacobian jac_wrt_nodes_structure_
std::array< std::array< JacobianRow, k3D >, k3D > JacRowMatrix
Eigen::SparseMatrix< double, Eigen::RowMajor > MatrixSXd
static MatrixSXd GetMdot(const EulerAngles &xyz, const EulerRates &xyz_d)
time derivative of GetM()
Vector3d GetAngularAccelerationInWorld(double t) const
Converts Euler angles, rates and rate derivatives o angular accelerations.
Eigen::SparseVector< double, Eigen::RowMajor > JacobianRow
Converts Euler angles and derivatives to angular quantities.
Jacobian GetDerivOfAngAccWrtEulerNodes(double t) const
Jacobian of the angular acceleration with respect to the Euler nodes.
static MatrixSXd GetM(const EulerAngles &xyz)
Matrix that maps euler rates to angular velocities in world.
Eigen::Quaterniond GetQuaternionBaseToWorld(double t) const
Converts the Euler angles at time t to a Quaternion.
Vector3d GetAngularVelocityInWorld(double t) const
Converts Euler angles and Euler rates to angular velocities.
Jacobian GetDerivMdotwrtNodes(double t, Dim3D dim) const
Derivative of the dim row of the time derivative of M with respect to the node values.
Vector3d EulerRates
derivative of the above
Vector3d EulerAngles
roll, pitch, yaw.
MatrixSXd GetRotationMatrixBaseToWorld(double t) const
Converts the Euler angles at time t to a rotation matrix.
Jacobian GetDerivOfAngVelWrtEulerNodes(double t) const
Jacobian of the angular velocity with respect to the Euler nodes.
Jacobian GetDerivMwrtNodes(double t, Dim3D dim) const
Derivative of the dim row of matrix M with respect to the node values.
Jacobian DerivOfRotVecMult(double t, const Vector3d &v, bool inverse) const
Returns the derivative of result of the linear equation M*v.
Dx
< the values or derivative. For motions e.g. position, velocity, ...
JacobianRow GetJac(double t, Dx deriv, Dim3D dim) const