Skip to content

Commit a800a75

Browse files
author
Felix Exner (fexner)
authored
Fix calibration (#704)
* Make calibration tests parametrizable * Fix calibration correction There was an error from using std::atan instead of std::atan2. In most cases that seemed to work fine, but with certain calibrations the calculated angle could end up in another quadrant, so atan was returning the wrong angle. We renamed a lot of variables and changed some of the docstrings in order to hopefully make things more understandable in the future. * Add a comment on test suite parametrization
1 parent 6ae99cc commit a800a75

File tree

2 files changed

+144
-99
lines changed

2 files changed

+144
-99
lines changed

ur_calibration/src/calibration.cpp

Lines changed: 47 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -56,68 +56,81 @@ void Calibration::correctAxis(const size_t link_index)
5656
// the kinematic structure gets destroyed, which has to be corrected:
5757
// - With setting d to 0, both the start and end points of the passive segment move along the
5858
// rotational axis of the start segment. Instead, the end point of the passive segment has to
59-
// move along the rotational axis of the next segment. This creates a change in a and and theta, if
59+
// move along the rotational axis of the next segment. This creates a change in a and theta, if
6060
// the two rotational axes are not parallel.
6161
//
6262
// - The length of moving along the next segment's rotational axis is calculated by intersecting
6363
// the rotational axis with the XY-plane of the first segment.
64+
//
65+
auto& d_theta_segment = chain_[2 * link_index];
66+
auto& a_alpha_segment = chain_[2 * link_index + 1];
67+
68+
auto& d = d_theta_segment(2, 3);
69+
auto& a = a_alpha_segment(0, 3);
6470

65-
if (chain_[2 * link_index](2, 3) == 0.0)
71+
if (d == 0.0)
6672
{
6773
// Nothing to do here.
6874
return;
6975
}
7076

71-
Eigen::Matrix4d fk_current = Eigen::Matrix4d::Identity();
72-
Eigen::Vector3d current_passive = Eigen::Vector3d::Zero();
77+
// Start of the next joint's d_theta segment relative to the joint before the current one
78+
Eigen::Matrix4d next_joint_root = Eigen::Matrix4d::Identity();
79+
next_joint_root *= d_theta_segment * a_alpha_segment;
7380

74-
Eigen::Matrix4d fk_next_passive = Eigen::Matrix4d::Identity();
75-
fk_next_passive *= chain_[link_index * 2] * chain_[link_index * 2 + 1];
76-
Eigen::Vector3d eigen_passive = fk_next_passive.topRightCorner(3, 1);
81+
Eigen::Vector3d next_root_position = next_joint_root.topRightCorner(3, 1);
7782

78-
Eigen::Vector3d eigen_next = (fk_next_passive * chain_[(link_index + 1) * 2]).topRightCorner(3, 1);
83+
const auto& next_d_theta_segment = chain_[(link_index + 1) * 2];
84+
Eigen::Vector3d next_d_theta_end = (next_joint_root * next_d_theta_segment).topRightCorner(3, 1);
7985

8086
// Construct a representation of the next segment's rotational axis
81-
Eigen::ParametrizedLine<double, 3> next_line;
82-
next_line = Eigen::ParametrizedLine<double, 3>::Through(eigen_passive, eigen_next);
87+
Eigen::ParametrizedLine<double, 3> next_rotation_axis;
88+
next_rotation_axis = Eigen::ParametrizedLine<double, 3>::Through(next_root_position, next_d_theta_end);
8389

84-
ROS_DEBUG_STREAM("next_line:" << std::endl
85-
<< "Base:" << std::endl
86-
<< next_line.origin() << std::endl
87-
<< "Direction:" << std::endl
88-
<< next_line.direction());
90+
ROS_DEBUG_STREAM("next rotation axis:" << std::endl
91+
<< "Base:" << std::endl
92+
<< next_rotation_axis.origin() << std::endl
93+
<< "Direction:" << std::endl
94+
<< next_rotation_axis.direction());
8995

9096
// XY-Plane of first segment's start
91-
Eigen::Hyperplane<double, 3> plane(fk_current.topLeftCorner(3, 3) * Eigen::Vector3d(0, 0, 1), current_passive);
92-
93-
// Intersect the rotation axis with the XY-Plane. We use both notations, the length and
94-
// intersection point, as we will need both. The intersection_param is the length moving along the
95-
// plane (change in the next segment's d param), while the intersection point will be used for
96-
// calculating the new angle theta.
97-
double intersection_param = next_line.intersectionParameter(plane);
98-
Eigen::Vector3d intersection = next_line.intersectionPoint(plane) - current_passive;
99-
double new_theta = std::atan(intersection.y() / intersection.x());
97+
Eigen::Hyperplane<double, 3> plane(Eigen::Vector3d(0, 0, 1), Eigen::Vector3d::Zero());
98+
99+
// Intersect the rotation axis of the next joint with the XY-Plane.
100+
// * The intersection_param is the length moving along the rotation axis until intersecting the plane.
101+
// * The intersection point will be used for calculating the new angle theta.
102+
double intersection_param = next_rotation_axis.intersectionParameter(plane);
103+
Eigen::Vector3d intersection_point = next_rotation_axis.intersectionPoint(plane);
104+
105+
// A non-zero a parameter will result in an intersection point at (a, 0) even without any
106+
// additional rotations. This effect has to be subtracted from the resulting theta value.
107+
double subtraction_angle = 0.0;
108+
if (std::abs(a) > 0)
109+
{
110+
// This is pi
111+
subtraction_angle = atan(1) * 4;
112+
}
113+
double new_theta = std::atan2(intersection_point.y(), intersection_point.x()) - subtraction_angle;
100114
// Upper and lower arm segments on URs all have negative length due to dh params
101-
double new_length = -1 * intersection.norm();
102-
ROS_DEBUG_STREAM("Wrist line intersecting at " << std::endl << intersection);
115+
double new_link_length = -1 * intersection_point.norm();
116+
ROS_DEBUG_STREAM("Next joint's rotation axis intersecting at " << std::endl << intersection_point);
103117
ROS_DEBUG_STREAM("Angle is " << new_theta);
104-
ROS_DEBUG_STREAM("Length is " << new_length);
118+
ROS_DEBUG_STREAM("Length is " << new_link_length);
105119
ROS_DEBUG_STREAM("Intersection param is " << intersection_param);
106120

107121
// as we move the passive segment towards the first segment, we have to move away the next segment
108122
// again, to keep the same kinematic structure.
109-
double sign_dir = next_line.direction().z() > 0 ? 1.0 : -1.0;
123+
double sign_dir = next_rotation_axis.direction().z() > 0 ? 1.0 : -1.0;
110124
double distance_correction = intersection_param * sign_dir;
111125

112126
// Set d parameter of the first segment to 0 and theta to the calculated new angle
113127
// Correct arm segment length and angle
114-
chain_[2 * link_index](2, 3) = 0.0;
115-
chain_[2 * link_index].topLeftCorner(3, 3) =
116-
Eigen::AngleAxisd(new_theta, Eigen::Vector3d::UnitZ()).toRotationMatrix();
128+
d = 0.0;
129+
d_theta_segment.topLeftCorner(3, 3) = Eigen::AngleAxisd(new_theta, Eigen::Vector3d::UnitZ()).toRotationMatrix();
117130

118131
// Correct arm segment length and angle
119-
chain_[2 * link_index + 1](0, 3) = new_length;
120-
chain_[2 * link_index + 1].topLeftCorner(3, 3) =
132+
a = new_link_length;
133+
a_alpha_segment.topLeftCorner(3, 3) =
121134
Eigen::AngleAxisd(robot_parameters_.segments_[link_index].theta_ - new_theta, Eigen::Vector3d::UnitZ())
122135
.toRotationMatrix() *
123136
Eigen::AngleAxisd(robot_parameters_.segments_[link_index].alpha_, Eigen::Vector3d::UnitX()).toRotationMatrix();
@@ -170,16 +183,7 @@ std::vector<Eigen::Matrix4d> Calibration::getSimplified() const
170183
simplified_chain.push_back(chain_[0]);
171184
for (size_t i = 1; i < chain_.size() - 1; i += 2)
172185
{
173-
simplified_chain.push_back(chain_[i] * chain_[i + 1]);
174-
Eigen::Matrix3d rot_a = chain_[i].topLeftCorner(3, 3);
175-
Eigen::Vector3d rpy_a = rot_a.eulerAngles(0, 1, 2);
176-
177-
Eigen::Matrix3d rot_b = chain_[i + 1].topLeftCorner(3, 3);
178-
Eigen::Vector3d rpy_b = rot_b.eulerAngles(0, 1, 2);
179-
180-
Eigen::Matrix3d rot = simplified_chain.back().topLeftCorner(3, 3);
181-
Eigen::Vector3d rpy = rot.eulerAngles(0, 1, 2);
182-
Eigen::Quaterniond quat(rot);
186+
simplified_chain.emplace_back(chain_[i] * chain_[i + 1]);
183187
}
184188
simplified_chain.push_back(chain_.back());
185189
return simplified_chain;

ur_calibration/test/calibration_test.cpp

Lines changed: 97 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -29,15 +29,18 @@
2929
#include <gtest/gtest.h>
3030
#include <ur_calibration/calibration.h>
3131

32-
using namespace ur_calibration;
32+
using ur_calibration::Calibration;
33+
using ur_calibration::DHRobot;
34+
using ur_calibration::DHSegment;
3335

34-
namespace
35-
{
36+
using CalibrationMat = Eigen::Matrix<double, 6, 4>;
37+
38+
/*
3639
bool isApproximately(const double val1, const double val2, const double precision)
3740
{
3841
return std::abs(val1 - val2) < precision;
3942
}
40-
43+
*/
4144
template <class Scalar_, int dim_>
4245
void doubleEqVec(const Eigen::Matrix<Scalar_, dim_, 1> vec1, const Eigen::Matrix<Scalar_, dim_, 1> vec2,
4346
const double precision)
@@ -48,21 +51,52 @@ void doubleEqVec(const Eigen::Matrix<Scalar_, dim_, 1> vec1, const Eigen::Matrix
4851
}
4952
}
5053

51-
TEST(UrRtdeDriver, ur10_fw_kinematics_ideal)
54+
DHRobot model_from_dh(std::array<double, 6> d, std::array<double, 6> a, std::array<double, 6> theta,
55+
std::array<double, 6> alpha)
5256
{
53-
DHRobot my_robot;
54-
const double pi = std::atan(1) * 4;
57+
DHRobot robot;
58+
for (size_t i = 0; i < 6; ++i)
59+
{
60+
robot.segments_.emplace_back(DHSegment(d[i], a[i], theta[i], alpha[i]));
61+
}
62+
return robot;
63+
}
5564

56-
// This is an ideal UR10
57-
// clang-format off
58-
my_robot.segments_.push_back(DHSegment(0.1273 , 0 , 0 , pi / 2));
59-
my_robot.segments_.push_back(DHSegment(0 , -0.612 , 0 , 0));
60-
my_robot.segments_.push_back(DHSegment(0 , -0.5723, 0 , 0.0));
61-
my_robot.segments_.push_back(DHSegment(0.163941, 0 , 0 , pi / 2));
62-
my_robot.segments_.push_back(DHSegment(0.1157 , 0 , 0 , -pi / 2));
63-
my_robot.segments_.push_back(DHSegment(0.0922 , 0 , 0 , 0));
64-
// clang-format on
65+
class CalibrationTest : public ::testing::TestWithParam<DHRobot>
66+
{
67+
public:
68+
void SetUp()
69+
{
70+
robot_models_.insert({ "ur10_ideal", model_from_dh({ 0.1273, 0, 0, 0.163941, 0.1157, 0.0922 }, // d
71+
{ 0, -0.612, -0.5723, 0, 0, 0 }, // a
72+
{ 0, 0, 0, 0, 0, 0 }, // theta
73+
{ pi / 2, 0, 0, pi / 2, -pi / 2, 0 } // alpha
74+
) });
75+
robot_models_.insert({ "ur10", model_from_dh({ 0.1273, 0, 0, 0.163941, 0.1157, 0.0922 }, // d
76+
{ 0, -0.612, -0.5723, 0, 0, 0 }, // a
77+
{ 0, 0, 0, 0, 0, 0 }, // theta
78+
{ pi_2, 0, 0, pi_2, -pi_2, 0 } // alpha
79+
) });
80+
robot_models_.insert({ "ur10e", model_from_dh({ 0.1807, 0, 0, 0.17415, 0.11985, 0.11655 }, // d
81+
{ 0, -0.6127, -0.57155, 0, 0, 0 }, // a
82+
{ 0, 0, 0, 0, 0, 0 }, // theta
83+
{ pi_2, 0, 0, pi_2, -pi_2, 0 } // alpha
84+
) });
85+
}
86+
void TearDown()
87+
{
88+
Test::TearDown();
89+
}
6590

91+
protected:
92+
const double pi = std::atan(1) * 4;
93+
const double pi_2 = 1.570796327; // This is what the simulated robot reports as pi/2
94+
std::map<std::string, DHRobot> robot_models_;
95+
};
96+
97+
TEST_F(CalibrationTest, ur10_fw_kinematics_ideal)
98+
{
99+
const auto& my_robot = robot_models_["ur10_ideal"];
66100
Calibration calibration(my_robot);
67101

68102
Eigen::Matrix<double, 6, 1> jointvalues;
@@ -84,26 +118,14 @@ TEST(UrRtdeDriver, ur10_fw_kinematics_ideal)
84118
my_robot.segments_[1].a_ / std::sqrt(2) + my_robot.segments_[2].a_ / std::sqrt(2),
85119
my_robot.segments_[0].d_ - my_robot.segments_[1].a_ / std::sqrt(2) + my_robot.segments_[2].a_ / std::sqrt(2) -
86120
my_robot.segments_[4].d_;
87-
doubleEqVec<double, 3>(expected_position, fk.topRightCorner(3, 1), 1e-16);
121+
doubleEqVec<double, 3>(expected_position, fk.topRightCorner(3, 1), 1e-8);
88122
}
89123
}
90124

91-
TEST(UrRtdeDriver, ur10_fw_kinematics_real)
125+
TEST_F(CalibrationTest, ur10_fw_kinematics_real)
92126
{
93127
// This test compares a corrected ideal model against positions taken from a simulated robot.
94-
DHRobot my_robot;
95-
const double pi_2 = 1.570796327; // This is what the simulated robot reports as pi/2
96-
97-
// This is an ideal UR10
98-
// clang-format off
99-
my_robot.segments_.push_back(DHSegment(0.1273 , 0 , 0 , pi_2));
100-
my_robot.segments_.push_back(DHSegment(0 , -0.612 , 0 , 0));
101-
my_robot.segments_.push_back(DHSegment(0 , -0.5723, 0 , 0.0));
102-
my_robot.segments_.push_back(DHSegment(0.163941, 0 , 0 , pi_2));
103-
my_robot.segments_.push_back(DHSegment(0.1157 , 0 , 0 , -pi_2));
104-
my_robot.segments_.push_back(DHSegment(0.0922 , 0 , 0 , 0));
105-
// clang-format on
106-
128+
const auto& my_robot = robot_models_["ur10"];
107129
Calibration calibration(my_robot);
108130

109131
Eigen::Matrix<double, 6, 1> jointvalues;
@@ -129,44 +151,27 @@ TEST(UrRtdeDriver, ur10_fw_kinematics_real)
129151

130152
doubleEqVec<double, 3>(expected_position, fk.topRightCorner(3, 1), 1e-15);
131153
}
154+
155+
TearDown();
132156
}
133157

134-
TEST(UrRtdeDriver, calibration)
158+
TEST_P(CalibrationTest, calibration)
135159
{
136160
// This test compares the forward kinematics of the model constructed from uncorrected
137161
// parameters with the one from the corrected parameters. They are tested against random
138162
// joint values and should be equal (in a numeric sense).
139163

140-
DHRobot my_robot;
141-
const double pi = std::atan(1) * 4;
164+
auto my_robot = robot_models_["ur10"];
165+
Calibration calibration(my_robot);
142166

143-
// This is an ideal UR10
144-
// clang-format off
145-
// d, a, theta, alpha
146-
my_robot.segments_.push_back(DHSegment(0.1273 , 0 , 0 , pi / 2));
147-
my_robot.segments_.push_back(DHSegment(0 , -0.612 , 0 , 0));
148-
my_robot.segments_.push_back(DHSegment(0 , -0.5723, 0 , 0.0));
149-
my_robot.segments_.push_back(DHSegment(0.163941, 0 , 0 , pi / 2));
150-
my_robot.segments_.push_back(DHSegment(0.1157 , 0 , 0 , -pi / 2));
151-
my_robot.segments_.push_back(DHSegment(0.0922 , 0 , 0 , 0));
152-
// clang-format on
153-
DHRobot my_robot_calibration;
154-
// clang-format off
155-
// d, a, theta, alpha
156-
my_robot_calibration.segments_.push_back(DHSegment( 0.00065609212979853 , 4.6311376834935676e-05 , -7.290070070824746e-05 , 0.000211987863869334 ));
157-
my_robot_calibration.segments_.push_back(DHSegment( 1.4442162376284788 , -0.00012568315331862312 , -0.01713897289704999 , -0.0072553625957652995));
158-
my_robot_calibration.segments_.push_back(DHSegment( 0.854147723854608 , 0.00186216581161458 , -0.03707159413492756 , -0.013483226769541364 ));
159-
my_robot_calibration.segments_.push_back(DHSegment(-2.2989425877563705 , 9.918593870679266e-05 , 0.054279462160583214 , 0.0013495820227329425 ));
160-
my_robot_calibration.segments_.push_back(DHSegment(-1.573498686836816e-05 , 4.215462720453189e-06 , 1.488984257025741e-07 , -0.001263136163679901 ));
161-
my_robot_calibration.segments_.push_back(DHSegment( 1.9072435590711256e-05 , 0 , 1.551499479707493e-05 , 0 ));
162-
// clang-format on
167+
auto robot_calibration = GetParam();
163168

164169
Eigen::Matrix<double, 6, 1> jointvalues;
165170
jointvalues << 0, 0, 0, 0, 0, 0;
166171

167172
for (size_t i = 0; i < 1000; ++i)
168173
{
169-
Calibration calibration(my_robot + my_robot_calibration);
174+
Calibration calibration(my_robot + robot_calibration);
170175
jointvalues = 2 * pi * Eigen::Matrix<double, 6, 1>::Random();
171176
Eigen::Matrix4d fk_orig = calibration.calcForwardKinematics(jointvalues);
172177
Eigen::Matrix3d rot_mat_orig = fk_orig.topLeftCorner(3, 3);
@@ -182,7 +187,43 @@ TEST(UrRtdeDriver, calibration)
182187
EXPECT_NEAR(angle_error, 0.0, 1e-12);
183188
}
184189
}
185-
} // namespace
190+
191+
// Tests are parametrized by both, the robot model (e.g. "ur10e") and the DH diff as they are stored on the robot
192+
// controller's calibration file.
193+
// The test will then assemble the DH parameters using the ones from the base model and the calibration.
194+
INSTANTIATE_TEST_SUITE_P(
195+
CalibrationTests, CalibrationTest,
196+
::testing::Values(
197+
model_from_dh({ 0.00065609212979853, 1.4442162376284788, 0.854147723854608, -2.2989425877563705,
198+
-1.573498686836816e-05, 1.9072435590711256e-05 }, // d
199+
{ 4.6311376834935676e-05, -0.00012568315331862312, 0.00186216581161458, 9.918593870679266e-05,
200+
4.215462720453189e-06, 0 }, // a
201+
{ -7.290070070824746e-05, -0.01713897289704999, -0.03707159413492756, 0.054279462160583214,
202+
1.488984257025741e-07, 1.551499479707493e-05 }, // theta
203+
{ 0.000211987863869334, -0.0072553625957652995, -0.013483226769541364, 0.0013495820227329425,
204+
-0.001263136163679901, 0 } // alpha
205+
),
206+
207+
model_from_dh({ -0.000144894975118076141, 303.469135666158195, -309.88394307789747, 6.41459904397394975,
208+
-4.48232900190081995e-05, -0.00087071402790364627 }, // d
209+
{ 0.000108651068627930392, 0.240324175250532346, 0.00180628180213493472, 2.63076149165684402e-05,
210+
3.96638632500012715e-06, 0 }, // a
211+
{ 1.59613525316931737e-07, -0.917209621528830232, 7.12936131346499469, 0.0710299029424392298,
212+
-1.64258976526054923e-06, 9.17286101034808787e-08 }, // theta
213+
{ -0.000444781952841921679, -0.00160215112531214153, 0.00631917793331091861,
214+
-0.00165055247340828437, 0.000763682515545038854, 0 } // alpha
215+
),
216+
model_from_dh({ -0.000160188285741325043, 439.140974079900957, -446.027059806332147, 6.88618689642360149,
217+
-3.86588496858186748e-05, -0.00087908274257374186 }, // d
218+
{ 2.12234865571205891e-05, 0.632017132627700651, 0.00229833638891230319, -4.61409023720933908e-05,
219+
-6.39280053471801522e-05, 0 }, // a
220+
{ -2.41478068943590252e-07, 1.60233952386694556, -1.68607190752171299, 0.0837331147700118711,
221+
-1.01260355871157781e-07, 3.91986209186123702e-08 }, // theta
222+
{ -0.000650246557584166496, 0.00139416666825590402, 0.00693818880325995126,
223+
-0.000811641562390219562, 0.000411120504570705592, 0 } // alpha
224+
)
225+
226+
));
186227

187228
int main(int argc, char* argv[])
188229
{

0 commit comments

Comments
 (0)