Blender V4.3
ConstraintSet.cpp
Go to the documentation of this file.
1/* SPDX-FileCopyrightText: 2009 Ruben Smits
2 *
3 * SPDX-License-Identifier: LGPL-2.1-or-later */
4
9#include "ConstraintSet.hpp"
11
12namespace iTaSC {
13
14ConstraintSet::ConstraintSet(unsigned int _nc,double accuracy,unsigned int maximum_iterations):
15 m_nc(_nc),
16 m_Cf(e_zero_matrix(m_nc,6)),
17 m_Wy(e_scalar_vector(m_nc,1.0)),
18 m_y(m_nc),m_ydot(e_zero_vector(m_nc)),m_chi(e_zero_vector(6)),
19 m_S(6),m_temp(6),m_tdelta(6),
20 m_Jf(e_identity_matrix(6,6)),
21 m_U(e_identity_matrix(6,6)),m_V(e_identity_matrix(6,6)),m_B(e_zero_matrix(6,6)),
22 m_Jf_inv(e_zero_matrix(6,6)),
23 m_internalPose(F_identity), m_externalPose(F_identity),
24 m_constraintCallback(NULL), m_constraintParam(NULL),
25 m_toggle(false),m_substep(false),
26 m_threshold(accuracy),m_maxIter(maximum_iterations)
27{
28 m_maxDeltaChi = e_scalar(0.52);
29}
30
32 m_nc(0),
33 m_internalPose(F_identity), m_externalPose(F_identity),
34 m_constraintCallback(NULL), m_constraintParam(NULL),
35 m_toggle(false),m_substep(false),
36 m_threshold(0.0),m_maxIter(0)
37{
38 m_maxDeltaChi = e_scalar(0.52);
39}
40
41void ConstraintSet::reset(unsigned int _nc,double accuracy,unsigned int maximum_iterations)
42{
43 m_nc = _nc;
48 m_B = e_zero_matrix(6,6);
55 m_S = e_zero_vector(6);
58 m_threshold = accuracy;
59 m_maxIter = maximum_iterations;
60}
61
65
66void ConstraintSet::modelUpdate(Frame& _external_pose,const Timestamp& timestamp)
67{
68 m_chi+=m_chidot*timestamp.realTimestep;
69 m_externalPose = _external_pose;
70
71 //update the internal pose and Jf
73 //check if loop is already closed, if not update the pose and Jf
74 unsigned int iter=0;
75 while(iter<5&&!closeLoop())
76 iter++;
77}
78
79double ConstraintSet::getMaxTimestep(double& timestep)
80{
81 e_scalar maxChidot = m_chidot.array().abs().maxCoeff();
82 if (timestep*maxChidot > m_maxDeltaChi) {
83 timestep = m_maxDeltaChi/maxChidot;
84 }
85 return timestep;
86}
87
89 m_externalPose=init_pose;
90 // get current Jf
92
93 unsigned int iter=0;
94 while(iter<m_maxIter&&!closeLoop()){
95 iter++;
96 }
97 if (iter<m_maxIter)
98 return true;
99 else
100 return false;
101}
102
103bool ConstraintSet::setControlParameter(int id, ConstraintAction action, double data, double timestep)
104{
105 ConstraintValues values;
107 values.values = &value;
108 values.number = 0;
109 values.action = action;
110 values.id = id;
111 value.action = action;
112 value.id = id;
113 switch (action) {
114 case ACT_NONE:
115 return true;
116 case ACT_VALUE:
117 value.yd = data;
118 values.number = 1;
119 break;
120 case ACT_VELOCITY:
121 value.yddot = data;
122 values.number = 1;
123 break;
124 case ACT_TOLERANCE:
125 values.tolerance = data;
126 break;
127 case ACT_FEEDBACK:
128 values.feedback = data;
129 break;
130 case ACT_ALPHA:
131 values.alpha = data;
132 break;
133 default:
134 assert(action==ACT_NONE);
135 break;
136 }
137 return setControlParameters(&values, 1, timestep);
138}
139
141 //Invert Jf
142 //TODO: svd_boost_Macie has problems if Jf contains zero-rows
143 //toggle=!toggle;
144 //svd_boost_Macie(Jf,U,S,V,B,temp,1e-3*threshold,toggle);
146 if(ret<0)
147 return false;
148
149 // the reference point and frame of the jacobian is the base frame
150 // m_externalPose-m_internalPose is the twist to extend the end effector
151 // to get the required pose => change the reference point to the base frame
153 twist_delta=twist_delta.RefPoint(-m_internalPose.p);
154 for(unsigned int i=0;i<6;i++)
155 m_tdelta(i)=twist_delta(i);
156 //TODO: use damping in constraintset inversion?
157 for(unsigned int i=0;i<6;i++) {
158 if(m_S(i)<m_threshold){
159 m_B.row(i).setConstant(0.0);
160 } else {
161 m_B.row(i) = m_U.col(i)/m_S(i);
162 }
163 }
164
165 m_Jf_inv.noalias()=m_V*m_B;
166
167 m_chi.noalias()+=m_Jf_inv*m_tdelta;
169 // m_externalPose-m_internalPose in end effector frame
170 // this is just to compare the pose, a different formula would work too
172
173}
174}
represents a frame transformation in 3D space (rotation + translation)
Definition frames.hpp:526
Vector p
origine of the Frame
Definition frames.hpp:528
Frame Inverse() const
Gives back inverse transformation of a Frame.
Definition frames.inl:431
represents both translational and rotational velocities.
Definition frames.hpp:679
Twist RefPoint(const Vector &v_base_AB) const
Definition frames.inl:322
virtual void updateJacobian()=0
bool setControlParameter(int id, ConstraintAction action, double value, double timestep=0.0)
virtual double getMaxTimestep(double &timestep)
virtual bool initialise(KDL::Frame &init_pose)
virtual void modelUpdate(KDL::Frame &_external_pose, const Timestamp &timestamp)
virtual void reset(unsigned int nc, double accuracy, unsigned int maximum_iterations)
virtual bool closeLoop()
virtual bool setControlParameters(ConstraintValues *_values, unsigned int _nvalues, double timestep=0.0)=0
#define NULL
#define e_scalar_vector
#define e_scalar
#define e_zero_vector
#define e_identity_matrix
#define e_zero_matrix
IMETHOD Vector diff(const Vector &a, const Vector &b, double dt=1)
int svd_eigen_HH(const Eigen::MatrixBase< MatrixA > &A, Eigen::MatrixBase< MatrixUV > &U, Eigen::MatrixBase< VectorS > &S, Eigen::MatrixBase< MatrixUV > &V, Eigen::MatrixBase< VectorS > &tmp, int maxiter=150)
IMETHOD bool Equal(const VectorAcc &, const VectorAcc &, double=epsilon)
const Frame F_identity
return ret
double realTimestep
Definition Cache.hpp:38