optimization_param_tests.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Fetch Robotics Inc.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 #include <gtest/gtest.h>
19 
20 TEST(ChainManagerTests, test_rosparam_loading)
21 {
22  ros::NodeHandle nh("~");
24  params.LoadFromROS(nh);
25 
26  EXPECT_EQ(static_cast<size_t>(14), params.free_params.size());
27 
28  EXPECT_EQ(static_cast<size_t>(2), params.free_frames.size());
29  EXPECT_EQ("head_camera_rgb_joint", params.free_frames[0].name);
30  EXPECT_TRUE(params.free_frames[0].x);
31  EXPECT_TRUE(params.free_frames[0].y);
32  EXPECT_FALSE(params.free_frames[1].roll);
33 
34  EXPECT_EQ(static_cast<size_t>(2), params.models.size());
35  EXPECT_EQ("arm", params.models[0].name);
36  EXPECT_EQ("chain", params.models[0].type);
37  EXPECT_EQ("gripper_led_frame", static_cast<std::string>(params.models[0].params["frame"]));
38 
39  EXPECT_EQ(static_cast<size_t>(2), params.error_blocks.size());
40  EXPECT_EQ("hand_eye", params.error_blocks[0].name);
41  EXPECT_EQ("camera3d_to_arm", params.error_blocks[0].type);
42  EXPECT_EQ("arm", static_cast<std::string>(params.error_blocks[0].params["arm"]));
43  EXPECT_EQ("camera", static_cast<std::string>(params.error_blocks[0].params["camera"]));
44 
45  EXPECT_EQ(static_cast<size_t>(1), params.free_frames_initial_values.size());
46  EXPECT_EQ("checkerboard", params.free_frames_initial_values[0].name);
47  EXPECT_EQ(0.0, params.free_frames_initial_values[0].x);
48  EXPECT_EQ(1.0, params.free_frames_initial_values[0].y);
49  EXPECT_EQ(2.0, params.free_frames_initial_values[0].z);
50 }
51 
52 int main(int argc, char** argv)
53 {
54  ros::init(argc, argv, "optimization_param_tests");
55  testing::InitGoogleTest(&argc, argv);
56  return RUN_ALL_TESTS();
57 }
Class to hold parameters for optimization.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< FreeFrameInitialValue > free_frames_initial_values
TEST(ChainManagerTests, test_rosparam_loading)
std::vector< std::string > free_params
int main(int argc, char **argv)
std::vector< FreeFrameParams > free_frames


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30