ft_calib.cpp
Go to the documentation of this file.
1 /*
2  * ft_calib.cpp
3  *
4  *
5  * Created on: Sep 26, 2012
6  * Authors: Francisco Viña
7  * fevb <at> kth.se
8  */
9 
10 /* Copyright (c) 2012, Francisco Viña, CVAP, KTH
11  All rights reserved.
12 
13  Redistribution and use in source and binary forms, with or without
14  modification, are permitted provided that the following conditions are met:
15  * Redistributions of source code must retain the above copyright
16  notice, this list of conditions and the following disclaimer.
17  * Redistributions in binary form must reproduce the above copyright
18  notice, this list of conditions and the following disclaimer in the
19  documentation and/or other materials provided with the distribution.
20  * Neither the name of KTH nor the
21  names of its contributors may be used to endorse or promote products
22  derived from this software without specific prior written permission.
23 
24  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
25  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
26  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27  DISCLAIMED. IN NO EVENT SHALL KTH BE LIABLE FOR ANY
28  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
29  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
31  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
32  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
33  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
34 */
35 
36 #include <ros/ros.h>
38 #include <Eigen/Dense>
39 #include <kdl/frameacc.hpp>
40 #include <kdl/frames.hpp>
41 
42 namespace Calibration{
43 
45 {
46  m_num_meas = 0;
47 }
48 
50 
51 }
52 
53 void FTCalib::addMeasurement(const geometry_msgs::Vector3Stamped &gravity,
54  const geometry_msgs::WrenchStamped &ft_raw)
55 {
56  if(gravity.header.frame_id != ft_raw.header.frame_id)
57  {
58  ROS_ERROR("Gravity vector and ft raw expressed in different frames (%s, %s)!",
59  gravity.header.frame_id.c_str(), ft_raw.header.frame_id.c_str());
60  return;
61  }
62 
63  m_num_meas++;
64 
65  Eigen::MatrixXd h = getMeasurementMatrix(gravity);
66  Eigen::VectorXd z = Eigen::Matrix<double, 6, 1>::Zero();
67  z(0) = ft_raw.wrench.force.x;
68  z(1) = ft_raw.wrench.force.y;
69  z(2) = ft_raw.wrench.force.z;
70 
71  z(3) = ft_raw.wrench.torque.x;
72  z(4) = ft_raw.wrench.torque.y;
73  z(5) = ft_raw.wrench.torque.z;
74 
75 
76 
77  if(m_num_meas==1)
78  {
79  H = h;
80  Z = z;
81  }
82 
83  else
84  {
85  Eigen::MatrixXd H_temp = H;
86  Eigen::VectorXd Z_temp = Z;
87 
88  H.resize(m_num_meas*6, 10);
89  Z.resize(m_num_meas*6);
90 
91  H.topRows((m_num_meas-1)*6) = H_temp;
92  Z.topRows((m_num_meas-1)*6) = Z_temp;
93 
94  H.bottomRows(6) = h;
95  Z.bottomRows(6) = z;
96  }
97 
98 
99 }
100 
101 
102 // Least squares to estimate the FT sensor parameters
103 Eigen::VectorXd FTCalib::getCalib()
104 {
105  Eigen::VectorXd ft_calib_params(10);
106 
107  ft_calib_params = H.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(Z);
108 
109  return ft_calib_params;
110 }
111 
112 
113 Eigen::MatrixXd FTCalib::getMeasurementMatrix(const geometry_msgs::Vector3Stamped &gravity)
114 {
116  KDL::Vector alpha = KDL::Vector::Zero();
118 
119  KDL::Vector g(gravity.vector.x, gravity.vector.y, gravity.vector.z);
120 
121  Eigen::MatrixXd H;
122  H = Eigen::Matrix<double, 6, 10>::Zero();
123 
124  for(unsigned int i=0; i<3; i++)
125  {
126  for(unsigned int j=4; j<10; j++)
127  {
128  if(i==j-4)
129  {
130  H(i,j) = 1.0;
131  }
132  else
133  {
134  H(i,j) = 0.0;
135  }
136  }
137  }
138 
139  for(unsigned int i=3; i<6; i++)
140  {
141  H(i,0) = 0.0;
142  }
143 
144  H(3,1) = 0.0;
145  H(4,2) = 0.0;
146  H(5,3) = 0.0;
147 
148  for(unsigned int i=0; i<3; i++)
149  {
150  H(i,0) = a(i) - g(i);
151  }
152 
153  H(0,1) = -w(1)*w(1) - w(2)*w(2);
154  H(0,2) = w(0)*w(1) - alpha(2);
155  H(0,3) = w(0)*w(2) + alpha(1);
156 
157  H(1,1) = w(0)*w(1) + alpha(2);
158  H(1,2) = -w(0)*w(0) - w(2)*w(2);
159  H(1,3) = w(1)*w(2) - alpha(0);
160 
161  H(2,1) = w(0)*w(2) - alpha(1);
162  H(2,2) = w(1)*w(2) + alpha(0);
163  H(2,3) = -w(1)*w(1) - w(0)*w(0);
164 
165  H(3,2) = a(2) - g(2);
166  H(3,3) = -a(1) + g(1);
167 
168 
169  H(4,1) = -a(2) + g(2);
170  H(4,3) = a(0) - g(0);
171 
172  H(5,1) = a(1) - g(1);
173  H(5,2) = -a(0) + g(0);
174 
175  for(unsigned int i=3; i<6; i++)
176  {
177  for(unsigned int j=4; j<10; j++)
178  {
179  if(i==(j-4))
180  {
181  H(i,j) = 1.0;
182  }
183  else
184  {
185  H(i,j) = 0.0;
186  }
187  }
188  }
189 
190 
191  return H;
192 }
193 
194 }
virtual void addMeasurement(const geometry_msgs::Vector3Stamped &gravity, const geometry_msgs::WrenchStamped &ft_raw)
Definition: ft_calib.cpp:53
virtual Eigen::MatrixXd getMeasurementMatrix(const geometry_msgs::Vector3Stamped &gravity)
Definition: ft_calib.cpp:113
virtual Eigen::VectorXd getCalib()
Definition: ft_calib.cpp:103
Eigen::VectorXd Z
Definition: ft_calib.h:85
unsigned int m_num_meas
Definition: ft_calib.h:88
Eigen::MatrixXd H
Definition: ft_calib.h:84
virtual ~FTCalib()
Definition: ft_calib.cpp:49
double z
TFSIMD_FORCE_INLINE const tfScalar & w() const
list a
#define ROS_ERROR(...)
static Vector Zero()


force_torque_sensor_calib
Author(s): Francisco Vina
autogenerated on Mon May 10 2021 02:27:43