chain_model_tests.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Michael Ferguson
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 
17 // Author: Gerardo Puga
18 
19 #include <gtest/gtest.h>
22 
24 
25 namespace {
26 
27 namespace test {
28 
31 
32 std::string robot_description =
33  "<?xml version='1.0' ?>"
34  "<robot name='test'>"
35  " <link name='link_0'/>"
36  " <joint name='first_joint' type='fixed'>"
37  " <origin rpy='0 0 0' xyz='1 1 1'/>"
38  " <parent link='link_0'/>"
39  " <child link='link_1'/>"
40  " </joint>"
41  " <link name='link_1'/>"
42  " <joint name='second_joint' type='revolute'>"
43  " <origin rpy='0 0 0' xyz='0 0 0'/>"
44  " <axis xyz='0 0 1'/>"
45  " <limit effort='30' lower='-1.57' upper='1.57' velocity='0.524'/>"
46  " <parent link='link_1'/>"
47  " <child link='link_2'/>"
48  " </joint>"
49  " <link name='link_2'/>"
50  " <joint name='third_joint' type='fixed'>"
51  " <origin rpy='0 -1.5 0' xyz='0 0 0.0526'/>"
52  " <parent link='link_2'/>"
53  " <child link='link_3'/>"
54  " </joint>"
55  " <link name='link_3'/>"
56  "</robot>";
57 
58 TEST(ChainModelTests, BadChainThrows)
59 {
60  KDL::Tree tree;
61 
63 
64  ASSERT_NO_THROW({ auto uut = ChainModel("uut", tree, "link_0", "link_3"); });
65 
66  ASSERT_THROW({ auto uut = ChainModel("uut", tree, "link_99", "link_3"); },
67  std::runtime_error);
68 
69  ASSERT_THROW({ auto uut = ChainModel("uut", tree, "link_0", "link_99"); },
70  std::runtime_error);
71 }
72 
73 TEST(Camera3dModelTests, BadChainThrows)
74 {
75  KDL::Tree tree;
76 
78 
79  ASSERT_NO_THROW(
80  { auto uut = Camera3dModel("uut", "uut", tree, "link_0", "link_3"); });
81 
82  ASSERT_THROW({ auto uut = Camera3dModel("uut", "uut", tree, "link_99", "link_3"); },
83  std::runtime_error);
84 
85  ASSERT_THROW({ auto uut = Camera3dModel("uut", "uut", tree, "link_0", "link_99"); },
86  std::runtime_error);
87 }
88 
89 }; // namespace test
90 
91 }; // namespace
92 
93 int main(int argc, char **argv)
94 {
95  testing::InitGoogleTest(&argc, argv);
96  return RUN_ALL_TESTS();
97 }
kdl_parser::treeFromString
KDL_PARSER_PUBLIC bool treeFromString(const std::string &xml, KDL::Tree &tree)
main
int main(int argc, char **argv)
Definition: chain_model_tests.cpp:93
robot_description
std::string robot_description
Definition: calibration_offset_parser_tests.cpp:7
test
chain.h
kdl_parser.hpp
TEST
TEST(CalibrationOffsetParserTests, test_urdf_update)
Definition: calibration_offset_parser_tests.cpp:60
robot_calibration::Camera3dModel
Model of a camera on a kinematic chain.
Definition: camera3d.h:31
camera3d.h
robot_calibration::ChainModel
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01