Blender V2.61 - r43446
|
00001 /* 00002 * Distance.hpp 00003 * 00004 * Created on: Jan 30, 2009 00005 * Author: rsmits 00006 */ 00007 00008 #ifndef DISTANCE_HPP_ 00009 #define DISTANCE_HPP_ 00010 00011 #include "ConstraintSet.hpp" 00012 #include "kdl/chain.hpp" 00013 #include "kdl/chainfksolverpos_recursive.hpp" 00014 #include "kdl/chainjnttojacsolver.hpp" 00015 00016 namespace iTaSC 00017 { 00018 00019 class Distance: public iTaSC::ConstraintSet 00020 { 00021 protected: 00022 virtual void updateKinematics(const Timestamp& timestamp); 00023 virtual void pushCache(const Timestamp& timestamp); 00024 virtual void updateJacobian(); 00025 virtual bool initialise(Frame& init_pose); 00026 virtual void initCache(Cache *_cache); 00027 virtual void updateControlOutput(const Timestamp& timestamp); 00028 virtual bool closeLoop(); 00029 00030 public: 00031 enum ID { 00032 ID_DISTANCE=1, 00033 }; 00034 Distance(double armlength=1.0, double accuracy=1e-6, unsigned int maximum_iterations=100); 00035 virtual ~Distance(); 00036 00037 virtual bool setControlParameters(struct ConstraintValues* _values, unsigned int _nvalues, double timestep); 00038 virtual const ConstraintValues* getControlParameters(unsigned int* _nvalues); 00039 00040 private: 00041 bool computeChi(Frame& pose); 00042 KDL::Chain m_chain; 00043 KDL::ChainFkSolverPos_recursive* m_fksolver; 00044 KDL::ChainJntToJacSolver* m_jacsolver; 00045 KDL::JntArray m_chiKdl; 00046 KDL::Jacobian m_jac; 00047 struct ConstraintSingleValue m_data; 00048 struct ConstraintValues m_values; 00049 Cache* m_cache; 00050 int m_distCCh; 00051 CacheTS m_distCTs; 00052 double m_maxerror; 00053 00054 void pushDist(CacheTS timestamp); 00055 bool popDist(CacheTS timestamp); 00056 00057 double m_alpha,m_yddot,m_yd,m_nextyd,m_nextyddot,m_K,m_tolerance; 00058 }; 00059 00060 } 00061 00062 #endif /* DISTANCE_HPP_ */