test_calibration.cpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
28 #include <gtest/gtest.h>
29 #include <ros/ros.h>
30 #include <vector>
31 
33 {
34 public:
36  {
37  }
38 
40  {
41  }
42 };
43 
45 // TWO POINTS TABLES //
47 
57 TEST(Calibration2Points, before)
58 {
59  std::vector<joint_calibration::Point> cal_table;
60 
62  point.raw_value = 1.0;
63  point.calibrated_value = 3.0;
64  cal_table.push_back(point);
65  point.raw_value = 2.0;
66  point.calibrated_value = 5.0;
67  cal_table.push_back(point);
68 
70 
71  EXPECT_EQ(cal->compute(0.0), 1.0);
72 
73  delete cal;
74 }
75 
85 TEST(Calibration2Points, in)
86 {
87  std::vector<joint_calibration::Point> cal_table;
88 
90  point.raw_value = 1.0;
91  point.calibrated_value = 3.0;
92  cal_table.push_back(point);
93  point.raw_value = 2.0;
94  point.calibrated_value = 5.0;
95  cal_table.push_back(point);
96 
98 
99  EXPECT_EQ(cal->compute(1.5), 4.0);
100  delete cal;
101 }
102 
112 TEST(Calibration2Points, after)
113 {
114  std::vector<joint_calibration::Point> cal_table;
115 
117  point.raw_value = 1.0;
118  point.calibrated_value = 3.0;
119  cal_table.push_back(point);
120  point.raw_value = 2.0;
121  point.calibrated_value = 5.0;
122  cal_table.push_back(point);
123 
125 
126  EXPECT_EQ(cal->compute(3.0), 7.0);
127  delete cal;
128 }
129 
139 TEST(Calibration2Points, on)
140 {
141  std::vector<joint_calibration::Point> cal_table;
142 
144  point.raw_value = 1.0;
145  point.calibrated_value = 3.0;
146  cal_table.push_back(point);
147  point.raw_value = 2.0;
148  point.calibrated_value = 5.0;
149  cal_table.push_back(point);
150 
152 
153  EXPECT_EQ(cal->compute(2.0), 5.0);
154  EXPECT_EQ(cal->compute(1.0), 3.0);
155  delete cal;
156 }
157 
158 
159 
161 // THREE POINTS TABLES //
163 
174 TEST(Calibration3Points, before)
175 {
176  std::vector<joint_calibration::Point> cal_table;
177 
179  point.raw_value = 1.0;
180  point.calibrated_value = 3.0;
181  cal_table.push_back(point);
182  point.raw_value = 2.0;
183  point.calibrated_value = 5.0;
184  cal_table.push_back(point);
185  point.raw_value = 3.0;
186  point.calibrated_value = 4.0;
187  cal_table.push_back(point);
188 
190 
191  EXPECT_EQ(cal->compute(0.0), 1.0);
192  delete cal;
193 }
194 
205 TEST(Calibration3Points, first_interval)
206 {
207  std::vector<joint_calibration::Point> cal_table;
208 
210  point.raw_value = 1.0;
211  point.calibrated_value = 3.0;
212  cal_table.push_back(point);
213  point.raw_value = 2.0;
214  point.calibrated_value = 5.0;
215  cal_table.push_back(point);
216  point.raw_value = 3.0;
217  point.calibrated_value = 4.0;
218  cal_table.push_back(point);
219 
221 
222  EXPECT_EQ(cal->compute(1.5), 4.0);
223  delete cal;
224 }
225 
236 TEST(Calibration3Points, second_interval)
237 {
238  std::vector<joint_calibration::Point> cal_table;
239 
241  point.raw_value = 1.0;
242  point.calibrated_value = 3.0;
243  cal_table.push_back(point);
244  point.raw_value = 2.0;
245  point.calibrated_value = 5.0;
246  cal_table.push_back(point);
247  point.raw_value = 3.0;
248  point.calibrated_value = 4.0;
249  cal_table.push_back(point);
250 
252 
253  EXPECT_EQ(cal->compute(2.5), 4.5);
254  delete cal;
255 }
256 
267 TEST(Calibration3Points, after)
268 {
269  std::vector<joint_calibration::Point> cal_table;
270 
272  point.raw_value = 1.0;
273  point.calibrated_value = 3.0;
274  cal_table.push_back(point);
275  point.raw_value = 2.0;
276  point.calibrated_value = 5.0;
277  cal_table.push_back(point);
278  point.raw_value = 3.0;
279  point.calibrated_value = 4.0;
280  cal_table.push_back(point);
281 
283 
284  EXPECT_EQ(cal->compute(4.0), 3.0);
285  delete cal;
286 }
287 
298 TEST(Calibration3Points, on)
299 {
300  std::vector<joint_calibration::Point> cal_table;
301 
303  point.raw_value = 1.0;
304  point.calibrated_value = 3.0;
305  cal_table.push_back(point);
306  point.raw_value = 2.0;
307  point.calibrated_value = 5.0;
308  cal_table.push_back(point);
309  point.raw_value = 3.0;
310  point.calibrated_value = 4.0;
311  cal_table.push_back(point);
312 
314 
315  EXPECT_EQ(cal->compute(1.0), 3.0);
316  EXPECT_EQ(cal->compute(2.0), 5.0);
317  EXPECT_EQ(cal->compute(3.0), 4.0);
318  delete cal;
319 }
320 
321 
344 TEST(Calibration5Points, mixed_and_big_test)
345 {
346  std::vector<joint_calibration::Point> cal_table;
347 
349 
350  point.raw_value = 5.0;
351  point.calibrated_value = 6.0;
352  cal_table.push_back(point);
353 
354  point.raw_value = 2.0;
355  point.calibrated_value = 0.0;
356  cal_table.push_back(point);
357 
358  point.raw_value = 1.0;
359  point.calibrated_value = -2.0;
360  cal_table.push_back(point);
361 
362  point.raw_value = 10.0;
363  point.calibrated_value = 0.0;
364  cal_table.push_back(point);
365 
366  point.raw_value = 3.0;
367  point.calibrated_value = -4.0;
368  cal_table.push_back(point);
369 
371 
372  EXPECT_EQ(cal->compute(0.0), -4.0);
373  EXPECT_EQ(cal->compute(1.0), -2.0);
374  EXPECT_EQ(cal->compute(1.5), -1.0);
375  EXPECT_EQ(cal->compute(2.0), 0.0);
376  EXPECT_EQ(cal->compute(2.5), -2.0);
377  EXPECT_EQ(cal->compute(3.0), -4.0);
378  EXPECT_EQ(cal->compute(4.0), 1.0);
379  EXPECT_EQ(cal->compute(5.0), 6.0);
380  EXPECT_EQ(cal->compute(7.5), 3.0);
381  EXPECT_EQ(cal->compute(10.), 0.0);
382  EXPECT_EQ(cal->compute(15.), -6.0);
383  delete cal;
384 }
385 
386 
387 
389 // MAIN //
391 
392 int main(int argc, char **argv)
393 {
394  ros::init(argc, argv, "calibration_test");
395 
396  testing::InitGoogleTest(&argc, argv);
397  return RUN_ALL_TESTS();
398 }
399 /* For the emacs weenies in the crowd.
400  Local Variables:
401  c-basic-offset: 2
402  End:
403 */
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
#define EXPECT_EQ(a, b)
TEST(Calibration2Points, before)
double compute(double raw_reading)
Definition: calibration.cpp:69
This class contains the algorithm which takes the raw ADC reading, and uses the N-point piecewise lin...


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:19