KdlChainIdRne.h
Go to the documentation of this file.
00001 #ifndef KDL_CHAIN_ID_RNE_H
00002 #define KDL_CHAIN_ID_RNE_H
00003 
00004 #include <kdl/chain.hpp>
00005 #include <kdl/frames.hpp>
00006 #include <kdl/jntarray.hpp>
00007 #include <kdl/chainidsolver.hpp>
00008 #include <kdl/rigidbodyinertia.hpp>
00009 #include <kdl/frames_io.hpp>
00010 
00011 
00027 class KdlChainIdRne {
00028     public:
00035         KdlChainIdRne(const KDL::Chain& chain, const KDL::Twist& v_base, const KDL::Twist& a_base);
00036         ~KdlChainIdRne(){};
00037         
00046         int KinematicsPass(const KDL::JntArray &q, const KDL::JntArray &q_dot, const KDL::JntArray &q_dotdot, KDL::Twist& v_out, KDL::Twist& a_out);
00047 
00057         int DynamicsPass(const KDL::Wrenches& f_ext,KDL::JntArray &torques, KDL::Wrench &f_base, std::vector<KDL::Wrench>& f, const KDL::RigidBodyInertia& I_ext, const KDL::RigidBodyInertia& I_seg, KDL::JntArray& Hv, KDL::RigidBodyInertia& I_base);
00058 
00059     private:
00060         KDL::Chain chain;
00061         unsigned int nj;
00062         unsigned int ns;
00063         std::vector<KDL::Frame> X;
00064         std::vector<KDL::Twist> S;
00065         std::vector<KDL::Twist> v;
00066         std::vector<KDL::Twist> a;
00067         std::vector<KDL::RigidBodyInertia> Ii;
00068         KDL::Wrench Fis;
00069         KDL::Twist vb;
00070         KDL::Twist ab;
00071 };
00072 
00073 #endif


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:53