test_calibration.cpp
Go to the documentation of this file.
1 
29 #include <gtest/gtest.h>
30 #include <ros/ros.h>
31 #include <vector>
32 
34 {
35 public:
37  {
38  }
39 
41  {
42  }
43 };
44 
46 // TWO POINTS TABLES //
48 
58 TEST(Calibration2Points, before)
59 {
60  std::vector<joint_calibration::Point> cal_table;
61 
63  point.raw_value = 1.0;
64  point.calibrated_value = 3.0;
65  cal_table.push_back(point);
66  point.raw_value = 2.0;
67  point.calibrated_value = 5.0;
68  cal_table.push_back(point);
69 
71 
72  EXPECT_EQ(cal->compute(0.0), 1.0);
73 
74  delete cal;
75 }
76 
86 TEST(Calibration2Points, in)
87 {
88  std::vector<joint_calibration::Point> cal_table;
89 
91  point.raw_value = 1.0;
92  point.calibrated_value = 3.0;
93  cal_table.push_back(point);
94  point.raw_value = 2.0;
95  point.calibrated_value = 5.0;
96  cal_table.push_back(point);
97 
99 
100  EXPECT_EQ(cal->compute(1.5), 4.0);
101  delete cal;
102 }
103 
113 TEST(Calibration2Points, after)
114 {
115  std::vector<joint_calibration::Point> cal_table;
116 
118  point.raw_value = 1.0;
119  point.calibrated_value = 3.0;
120  cal_table.push_back(point);
121  point.raw_value = 2.0;
122  point.calibrated_value = 5.0;
123  cal_table.push_back(point);
124 
126 
127  EXPECT_EQ(cal->compute(3.0), 7.0);
128  delete cal;
129 }
130 
140 TEST(Calibration2Points, on)
141 {
142  std::vector<joint_calibration::Point> cal_table;
143 
145  point.raw_value = 1.0;
146  point.calibrated_value = 3.0;
147  cal_table.push_back(point);
148  point.raw_value = 2.0;
149  point.calibrated_value = 5.0;
150  cal_table.push_back(point);
151 
153 
154  EXPECT_EQ(cal->compute(2.0), 5.0);
155  EXPECT_EQ(cal->compute(1.0), 3.0);
156  delete cal;
157 }
158 
159 
160 
162 // THREE POINTS TABLES //
164 
175 TEST(Calibration3Points, before)
176 {
177  std::vector<joint_calibration::Point> cal_table;
178 
180  point.raw_value = 1.0;
181  point.calibrated_value = 3.0;
182  cal_table.push_back(point);
183  point.raw_value = 2.0;
184  point.calibrated_value = 5.0;
185  cal_table.push_back(point);
186  point.raw_value = 3.0;
187  point.calibrated_value = 4.0;
188  cal_table.push_back(point);
189 
191 
192  EXPECT_EQ(cal->compute(0.0), 1.0);
193  delete cal;
194 }
195 
206 TEST(Calibration3Points, first_interval)
207 {
208  std::vector<joint_calibration::Point> cal_table;
209 
211  point.raw_value = 1.0;
212  point.calibrated_value = 3.0;
213  cal_table.push_back(point);
214  point.raw_value = 2.0;
215  point.calibrated_value = 5.0;
216  cal_table.push_back(point);
217  point.raw_value = 3.0;
218  point.calibrated_value = 4.0;
219  cal_table.push_back(point);
220 
222 
223  EXPECT_EQ(cal->compute(1.5), 4.0);
224  delete cal;
225 }
226 
237 TEST(Calibration3Points, second_interval)
238 {
239  std::vector<joint_calibration::Point> cal_table;
240 
242  point.raw_value = 1.0;
243  point.calibrated_value = 3.0;
244  cal_table.push_back(point);
245  point.raw_value = 2.0;
246  point.calibrated_value = 5.0;
247  cal_table.push_back(point);
248  point.raw_value = 3.0;
249  point.calibrated_value = 4.0;
250  cal_table.push_back(point);
251 
253 
254  EXPECT_EQ(cal->compute(2.5), 4.5);
255  delete cal;
256 }
257 
268 TEST(Calibration3Points, after)
269 {
270  std::vector<joint_calibration::Point> cal_table;
271 
273  point.raw_value = 1.0;
274  point.calibrated_value = 3.0;
275  cal_table.push_back(point);
276  point.raw_value = 2.0;
277  point.calibrated_value = 5.0;
278  cal_table.push_back(point);
279  point.raw_value = 3.0;
280  point.calibrated_value = 4.0;
281  cal_table.push_back(point);
282 
284 
285  EXPECT_EQ(cal->compute(4.0), 3.0);
286  delete cal;
287 }
288 
299 TEST(Calibration3Points, on)
300 {
301  std::vector<joint_calibration::Point> cal_table;
302 
304  point.raw_value = 1.0;
305  point.calibrated_value = 3.0;
306  cal_table.push_back(point);
307  point.raw_value = 2.0;
308  point.calibrated_value = 5.0;
309  cal_table.push_back(point);
310  point.raw_value = 3.0;
311  point.calibrated_value = 4.0;
312  cal_table.push_back(point);
313 
315 
316  EXPECT_EQ(cal->compute(1.0), 3.0);
317  EXPECT_EQ(cal->compute(2.0), 5.0);
318  EXPECT_EQ(cal->compute(3.0), 4.0);
319  delete cal;
320 }
321 
322 
345 TEST(Calibration5Points, mixed_and_big_test)
346 {
347  std::vector<joint_calibration::Point> cal_table;
348 
350 
351  point.raw_value = 5.0;
352  point.calibrated_value = 6.0;
353  cal_table.push_back(point);
354 
355  point.raw_value = 2.0;
356  point.calibrated_value = 0.0;
357  cal_table.push_back(point);
358 
359  point.raw_value = 1.0;
360  point.calibrated_value = -2.0;
361  cal_table.push_back(point);
362 
363  point.raw_value = 10.0;
364  point.calibrated_value = 0.0;
365  cal_table.push_back(point);
366 
367  point.raw_value = 3.0;
368  point.calibrated_value = -4.0;
369  cal_table.push_back(point);
370 
372 
373  EXPECT_EQ(cal->compute(0.0), -4.0);
374  EXPECT_EQ(cal->compute(1.0), -2.0);
375  EXPECT_EQ(cal->compute(1.5), -1.0);
376  EXPECT_EQ(cal->compute(2.0), 0.0);
377  EXPECT_EQ(cal->compute(2.5), -2.0);
378  EXPECT_EQ(cal->compute(3.0), -4.0);
379  EXPECT_EQ(cal->compute(4.0), 1.0);
380  EXPECT_EQ(cal->compute(5.0), 6.0);
381  EXPECT_EQ(cal->compute(7.5), 3.0);
382  EXPECT_EQ(cal->compute(10.), 0.0);
383  EXPECT_EQ(cal->compute(15.), -6.0);
384  delete cal;
385 }
386 
387 
388 
390 // MAIN //
392 
393 int main(int argc, char **argv)
394 {
395  ros::init(argc, argv, "calibration_test");
396 
397  testing::InitGoogleTest(&argc, argv);
398  return RUN_ALL_TESTS();
399 }
400 /* For the emacs weenies in the crowd.
401  Local Variables:
402  c-basic-offset: 2
403  End:
404 */
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
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 Tue Oct 13 2020 03:55:49