29 #include <gtest/gtest.h> 58 TEST(Calibration2Points, before)
60 std::vector<joint_calibration::Point> cal_table;
65 cal_table.push_back(point);
68 cal_table.push_back(point);
72 EXPECT_EQ(cal->
compute(0.0), 1.0);
86 TEST(Calibration2Points, in)
88 std::vector<joint_calibration::Point> cal_table;
93 cal_table.push_back(point);
96 cal_table.push_back(point);
100 EXPECT_EQ(cal->
compute(1.5), 4.0);
113 TEST(Calibration2Points, after)
115 std::vector<joint_calibration::Point> cal_table;
120 cal_table.push_back(point);
123 cal_table.push_back(point);
127 EXPECT_EQ(cal->
compute(3.0), 7.0);
142 std::vector<joint_calibration::Point> cal_table;
147 cal_table.push_back(point);
150 cal_table.push_back(point);
154 EXPECT_EQ(cal->
compute(2.0), 5.0);
155 EXPECT_EQ(cal->
compute(1.0), 3.0);
175 TEST(Calibration3Points, before)
177 std::vector<joint_calibration::Point> cal_table;
182 cal_table.push_back(point);
185 cal_table.push_back(point);
188 cal_table.push_back(point);
192 EXPECT_EQ(cal->
compute(0.0), 1.0);
206 TEST(Calibration3Points, first_interval)
208 std::vector<joint_calibration::Point> cal_table;
213 cal_table.push_back(point);
216 cal_table.push_back(point);
219 cal_table.push_back(point);
223 EXPECT_EQ(cal->
compute(1.5), 4.0);
237 TEST(Calibration3Points, second_interval)
239 std::vector<joint_calibration::Point> cal_table;
244 cal_table.push_back(point);
247 cal_table.push_back(point);
250 cal_table.push_back(point);
254 EXPECT_EQ(cal->
compute(2.5), 4.5);
268 TEST(Calibration3Points, after)
270 std::vector<joint_calibration::Point> cal_table;
275 cal_table.push_back(point);
278 cal_table.push_back(point);
281 cal_table.push_back(point);
285 EXPECT_EQ(cal->
compute(4.0), 3.0);
301 std::vector<joint_calibration::Point> cal_table;
306 cal_table.push_back(point);
309 cal_table.push_back(point);
312 cal_table.push_back(point);
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);
345 TEST(Calibration5Points, mixed_and_big_test)
347 std::vector<joint_calibration::Point> cal_table;
353 cal_table.push_back(point);
357 cal_table.push_back(point);
361 cal_table.push_back(point);
365 cal_table.push_back(point);
369 cal_table.push_back(point);
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);
393 int main(
int argc,
char **argv)
395 ros::init(argc, argv,
"calibration_test");
397 testing::InitGoogleTest(&argc, argv);
398 return RUN_ALL_TESTS();
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)
This class contains the algorithm which takes the raw ADC reading, and uses the N-point piecewise lin...