optimization_param_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2014 Fetch Robotics Inc.
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include <robot_calibration/ceres/optimization_params.h>
00018 #include <gtest/gtest.h>
00019 
00020 TEST(ChainManagerTests, test_rosparam_loading)
00021 {
00022   ros::NodeHandle nh("~");
00023   robot_calibration::OptimizationParams params;
00024   params.LoadFromROS(nh);
00025 
00026   EXPECT_EQ(14, params.free_params.size());
00027 
00028   EXPECT_EQ(2, params.free_frames.size());
00029   EXPECT_EQ("head_camera_rgb_joint", params.free_frames[0].name);
00030   EXPECT_TRUE(params.free_frames[0].x);
00031   EXPECT_TRUE(params.free_frames[0].y);
00032   EXPECT_FALSE(params.free_frames[1].roll);
00033 
00034   EXPECT_EQ(2, params.models.size());
00035   EXPECT_EQ("arm", params.models[0].name);
00036   EXPECT_EQ("chain", params.models[0].type);
00037   EXPECT_EQ("gripper_led_frame", static_cast<std::string>(params.models[0].params["frame"]));
00038 
00039   EXPECT_EQ(2, params.error_blocks.size());
00040   EXPECT_EQ("hand_eye", params.error_blocks[0].name);
00041   EXPECT_EQ("camera3d_to_arm", params.error_blocks[0].type);
00042   EXPECT_EQ("arm", static_cast<std::string>(params.error_blocks[0].params["arm"]));
00043   EXPECT_EQ("camera", static_cast<std::string>(params.error_blocks[0].params["camera"]));
00044 }
00045 
00046 int main(int argc, char** argv)
00047 {
00048   ros::init(argc, argv, "optimization_param_tests");
00049   testing::InitGoogleTest(&argc, argv);
00050   return RUN_ALL_TESTS();
00051 }


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31