chain_manager_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2014-2015 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/capture/chain_manager.h>
00018 #include <gtest/gtest.h>
00019 
00020 TEST(ChainManagerTests, test_rosparam_loading)
00021 {
00022   ros::NodeHandle nh("~");
00023   robot_calibration::ChainManager manager(nh, 0.001);
00024 
00025   std::vector<std::string> chain_names = manager.getChains();
00026   EXPECT_EQ(2, chain_names.size());
00027 
00028   std::vector<std::string> joint_names = manager.getChainJointNames("arm");
00029   EXPECT_EQ(7, joint_names.size());
00030   EXPECT_EQ("arm_lift_joint", joint_names[0]);
00031   EXPECT_EQ("arm_shoulder_pan_joint", joint_names[1]);
00032   EXPECT_EQ("arm_shoulder_lift_joint", joint_names[2]);
00033   EXPECT_EQ("arm_upperarm_roll_joint", joint_names[3]);
00034   EXPECT_EQ("arm_elbow_flex_joint", joint_names[4]);
00035   EXPECT_EQ("arm_wrist_flex_joint", joint_names[5]);
00036   EXPECT_EQ("arm_wrist_roll_joint", joint_names[6]);
00037 
00038   joint_names = manager.getChainJointNames("not_a_chain");
00039   EXPECT_EQ(0, joint_names.size());
00040 
00041   joint_names = manager.getChainJointNames("head");
00042   EXPECT_EQ(2, joint_names.size());
00043   EXPECT_EQ("head_pan_joint", joint_names[0]);
00044   EXPECT_EQ("head_tilt_joint", joint_names[1]);
00045 
00046   std::string group_name = manager.getPlanningGroupName("arm");
00047   EXPECT_EQ("arm_group", group_name);
00048 
00049   group_name = manager.getPlanningGroupName("head");
00050   EXPECT_EQ("", group_name);
00051 }
00052 
00053 int main(int argc, char** argv)
00054 {
00055   ros::init(argc, argv, "chain_manager_tests");
00056   testing::InitGoogleTest(&argc, argv);
00057   return RUN_ALL_TESTS();
00058 }


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