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_MODELS_DYNAMIC_MODEL_H_
00031 #define TOWR_MODELS_DYNAMIC_MODEL_H_
00032
00033 #include <memory>
00034 #include <vector>
00035
00036 #include <Eigen/Dense>
00037 #include <Eigen/Sparse>
00038
00039 #include <towr/variables/euler_converter.h>
00040
00041 namespace towr {
00042
00058 class DynamicModel {
00059 public:
00060 using Ptr = std::shared_ptr<DynamicModel>;
00061 using Vector3d = Eigen::Vector3d;
00062 using Matrix3d = Eigen::Matrix3d;
00063 using ComPos = Eigen::Vector3d;
00064 using AngVel = Eigen::Vector3d;
00065 using BaseAcc = Eigen::Matrix<double,6,1>;
00066 using Jac = Eigen::SparseMatrix<double, Eigen::RowMajor>;
00067 using EEPos = std::vector<Eigen::Vector3d>;
00068 using EELoad = EEPos;
00069 using EE = uint;
00070
00081 void SetCurrent(const ComPos& com_W, const Vector3d com_acc_W,
00082 const Matrix3d& w_R_b, const AngVel& omega_W, const Vector3d& omega_dot_W,
00083 const EELoad& force_W, const EEPos& pos_W);
00084
00089 virtual BaseAcc GetDynamicViolation() const = 0;
00090
00099 virtual Jac GetJacobianWrtBaseLin(const Jac& jac_base_lin_pos,
00100 const Jac& jac_base_lin_acc) const = 0;
00101
00110 virtual Jac GetJacobianWrtBaseAng(const EulerConverter& base_angular,
00111 double t) const = 0;
00112
00121 virtual Jac GetJacobianWrtForce(const Jac& ee_force, EE ee) const = 0;
00122
00131 virtual Jac GetJacobianWrtEEPos(const Jac& ee_pos, EE ee) const = 0;
00132
00136 double g() const { return g_; };
00137
00141 double m() const { return m_; };
00142
00146 int GetEECount() const { return ee_pos_.size(); };
00147
00148 protected:
00149 ComPos com_pos_;
00150 Vector3d com_acc_;
00151
00152 Matrix3d w_R_b_;
00153 AngVel omega_;
00154 Vector3d omega_dot_;
00155
00156 EEPos ee_pos_;
00157 EELoad ee_force_;
00158
00163 DynamicModel(double mass, int ee_count);
00164 virtual ~DynamicModel () = default;
00165
00166 private:
00167 double g_;
00168 double m_;
00169 };
00170
00171 }
00172
00173 #endif