ConstraintSet.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177
  1. /** \file itasc/ConstraintSet.cpp
  2. * \ingroup itasc
  3. */
  4. /*
  5. * ConstraintSet.cpp
  6. *
  7. * Created on: Jan 5, 2009
  8. * Author: rubensmits
  9. */
  10. #include "ConstraintSet.hpp"
  11. #include "kdl/utilities/svd_eigen_HH.hpp"
  12. namespace iTaSC {
  13. ConstraintSet::ConstraintSet(unsigned int _nc,double accuracy,unsigned int maximum_iterations):
  14. m_nc(_nc),
  15. m_Cf(e_zero_matrix(m_nc,6)),
  16. m_Wy(e_scalar_vector(m_nc,1.0)),
  17. m_y(m_nc),m_ydot(e_zero_vector(m_nc)),m_chi(e_zero_vector(6)),
  18. m_S(6),m_temp(6),m_tdelta(6),
  19. m_Jf(e_identity_matrix(6,6)),
  20. m_U(e_identity_matrix(6,6)),m_V(e_identity_matrix(6,6)),m_B(e_zero_matrix(6,6)),
  21. m_Jf_inv(e_zero_matrix(6,6)),
  22. m_internalPose(F_identity), m_externalPose(F_identity),
  23. m_constraintCallback(NULL), m_constraintParam(NULL),
  24. m_toggle(false),m_substep(false),
  25. m_threshold(accuracy),m_maxIter(maximum_iterations)
  26. {
  27. m_maxDeltaChi = e_scalar(0.52);
  28. }
  29. ConstraintSet::ConstraintSet():
  30. m_nc(0),
  31. m_internalPose(F_identity), m_externalPose(F_identity),
  32. m_constraintCallback(NULL), m_constraintParam(NULL),
  33. m_toggle(false),m_substep(false),
  34. m_threshold(0.0),m_maxIter(0)
  35. {
  36. m_maxDeltaChi = e_scalar(0.52);
  37. }
  38. void ConstraintSet::reset(unsigned int _nc,double accuracy,unsigned int maximum_iterations)
  39. {
  40. m_nc = _nc;
  41. m_Jf = e_identity_matrix(6,6);
  42. m_Cf = e_zero_matrix(m_nc,6);
  43. m_U = e_identity_matrix(6,6);
  44. m_V = e_identity_matrix(6,6);
  45. m_B = e_zero_matrix(6,6);
  46. m_Jf_inv = e_zero_matrix(6,6),
  47. m_Wy = e_scalar_vector(m_nc,1.0),
  48. m_chi = e_zero_vector(6);
  49. m_chidot = e_zero_vector(6);
  50. m_y = e_zero_vector(m_nc);
  51. m_ydot = e_zero_vector(m_nc);
  52. m_S = e_zero_vector(6);
  53. m_temp = e_zero_vector(6);
  54. m_tdelta = e_zero_vector(6);
  55. m_threshold = accuracy;
  56. m_maxIter = maximum_iterations;
  57. }
  58. ConstraintSet::~ConstraintSet() {
  59. }
  60. void ConstraintSet::modelUpdate(Frame& _external_pose,const Timestamp& timestamp)
  61. {
  62. m_chi+=m_chidot*timestamp.realTimestep;
  63. m_externalPose = _external_pose;
  64. //update the internal pose and Jf
  65. updateJacobian();
  66. //check if loop is already closed, if not update the pose and Jf
  67. unsigned int iter=0;
  68. while(iter<5&&!closeLoop())
  69. iter++;
  70. }
  71. double ConstraintSet::getMaxTimestep(double& timestep)
  72. {
  73. e_scalar maxChidot = m_chidot.array().abs().maxCoeff();
  74. if (timestep*maxChidot > m_maxDeltaChi) {
  75. timestep = m_maxDeltaChi/maxChidot;
  76. }
  77. return timestep;
  78. }
  79. bool ConstraintSet::initialise(Frame& init_pose){
  80. m_externalPose=init_pose;
  81. // get current Jf
  82. updateJacobian();
  83. unsigned int iter=0;
  84. while(iter<m_maxIter&&!closeLoop()){
  85. iter++;
  86. }
  87. if (iter<m_maxIter)
  88. return true;
  89. else
  90. return false;
  91. }
  92. bool ConstraintSet::setControlParameter(int id, ConstraintAction action, double data, double timestep)
  93. {
  94. ConstraintValues values;
  95. ConstraintSingleValue value;
  96. values.values = &value;
  97. values.number = 0;
  98. values.action = action;
  99. values.id = id;
  100. value.action = action;
  101. value.id = id;
  102. switch (action) {
  103. case ACT_NONE:
  104. return true;
  105. case ACT_VALUE:
  106. value.yd = data;
  107. values.number = 1;
  108. break;
  109. case ACT_VELOCITY:
  110. value.yddot = data;
  111. values.number = 1;
  112. break;
  113. case ACT_TOLERANCE:
  114. values.tolerance = data;
  115. break;
  116. case ACT_FEEDBACK:
  117. values.feedback = data;
  118. break;
  119. case ACT_ALPHA:
  120. values.alpha = data;
  121. break;
  122. default:
  123. assert(action==ACT_NONE);
  124. break;
  125. }
  126. return setControlParameters(&values, 1, timestep);
  127. }
  128. bool ConstraintSet::closeLoop(){
  129. //Invert Jf
  130. //TODO: svd_boost_Macie has problems if Jf contains zero-rows
  131. //toggle=!toggle;
  132. //svd_boost_Macie(Jf,U,S,V,B,temp,1e-3*threshold,toggle);
  133. int ret = KDL::svd_eigen_HH(m_Jf,m_U,m_S,m_V,m_temp);
  134. if(ret<0)
  135. return false;
  136. // the reference point and frame of the jacobian is the base frame
  137. // m_externalPose-m_internalPose is the twist to extend the end effector
  138. // to get the required pose => change the reference point to the base frame
  139. Twist twist_delta(diff(m_internalPose,m_externalPose));
  140. twist_delta=twist_delta.RefPoint(-m_internalPose.p);
  141. for(unsigned int i=0;i<6;i++)
  142. m_tdelta(i)=twist_delta(i);
  143. //TODO: use damping in constraintset inversion?
  144. for(unsigned int i=0;i<6;i++) {
  145. if(m_S(i)<m_threshold){
  146. m_B.row(i).setConstant(0.0);
  147. } else {
  148. m_B.row(i) = m_U.col(i)/m_S(i);
  149. }
  150. }
  151. m_Jf_inv.noalias()=m_V*m_B;
  152. m_chi.noalias()+=m_Jf_inv*m_tdelta;
  153. updateJacobian();
  154. // m_externalPose-m_internalPose in end effector frame
  155. // this is just to compare the pose, a different formula would work too
  156. return Equal(m_internalPose.Inverse()*m_externalPose,F_identity,m_threshold);
  157. }
  158. }