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
00066 class DynamicModel {
00067 public:
00068 using Ptr = std::shared_ptr<DynamicModel>;
00069 using Vector3d = Eigen::Vector3d;
00070 using Matrix3d = Eigen::Matrix3d;
00071 using ComPos = Eigen::Vector3d;
00072 using AngVel = Eigen::Vector3d;
00073 using BaseAcc = Eigen::Matrix<double,6,1>;
00074 using Jac = Eigen::SparseMatrix<double, Eigen::RowMajor>;
00075 using EEPos = std::vector<Eigen::Vector3d>;
00076 using EELoad = EEPos;
00077 using EE = uint;
00078
00089 void SetCurrent(const ComPos& com_W, const Vector3d com_acc_W,
00090 const Matrix3d& w_R_b, const AngVel& omega_W, const Vector3d& omega_dot_W,
00091 const EELoad& force_W, const EEPos& pos_W);
00092
00097 virtual BaseAcc GetDynamicViolation() const = 0;
00098
00107 virtual Jac GetJacobianWrtBaseLin(const Jac& jac_base_lin_pos,
00108 const Jac& jac_base_lin_acc) const = 0;
00109
00118 virtual Jac GetJacobianWrtBaseAng(const EulerConverter& base_angular,
00119 double t) const = 0;
00120
00129 virtual Jac GetJacobianWrtForce(const Jac& ee_force, EE ee) const = 0;
00130
00139 virtual Jac GetJacobianWrtEEPos(const Jac& ee_pos, EE ee) const = 0;
00140
00144 double g() const { return g_; };
00145
00149 double m() const { return m_; };
00150
00154 int GetEECount() const { return ee_pos_.size(); };
00155
00156 protected:
00157 ComPos com_pos_;
00158 Vector3d com_acc_;
00159
00160 Matrix3d w_R_b_;
00161 AngVel omega_;
00162 Vector3d omega_dot_;
00163
00164 EEPos ee_pos_;
00165 EELoad ee_force_;
00166
00171 DynamicModel(double mass, int ee_count);
00172 virtual ~DynamicModel () = default;
00173
00174 private:
00175 double g_;
00176 double m_;
00177 };
00178
00179 }
00180
00181 #endif