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 #ifndef KDL_CHAIN_FDSOLVER_RECURSIVE_NEWTON_EULER_HPP
00023 #define KDL_CHAIN_FDSOLVER_RECURSIVE_NEWTON_EULER_HPP
00024
00025 #include "chainfdsolver.hpp"
00026 #include "chainidsolver_recursive_newton_euler.hpp"
00027 #include "chaindynparam.hpp"
00028
00029 namespace KDL{
00042 class ChainFdSolver_RNE : public ChainFdSolver{
00043 public:
00049 ChainFdSolver_RNE(const Chain& chain, Vector grav);
00050 ~ChainFdSolver_RNE(){};
00051
00062 int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &torques, const Wrenches& f_ext, JntArray &q_dotdot);
00063
00065 virtual void updateInternalDataStructures();
00066
00089 void RK4Integrator(int& nj, const double& t, double& dt, KDL::JntArray& q, KDL::JntArray& q_dot,
00090 KDL::JntArray& torques, KDL::Wrenches& f_ext, KDL::ChainFdSolver_RNE& fdsolver,
00091 KDL::JntArray& q_dotdot, KDL::JntArray& dq, KDL::JntArray& dq_dot,
00092 KDL::JntArray& q_temp, KDL::JntArray& q_dot_temp);
00093
00094 private:
00095 const Chain& chain;
00096 ChainDynParam DynSolver;
00097 ChainIdSolver_RNE IdSolver;
00098 unsigned int nj;
00099 unsigned int ns;
00100 JntArray Tzeroacc;
00101 JntSpaceInertiaMatrix H;
00102 Eigen::MatrixXd H_eig;
00103 Eigen::VectorXd Tzeroacc_eig;
00104 Eigen::MatrixXd L_eig;
00105 Eigen::VectorXd D_eig;
00106 Eigen::VectorXd r_eig;
00107 Eigen::VectorXd acc_eig;
00108 };
00109 }
00110
00111 #endif