tesseract_urdf_limits_unit.cpp
Go to the documentation of this file.
3 #include <iostream>
4 
5 #include <gtest/gtest.h>
6 #include <Eigen/Geometry>
8 
10 #include <tesseract_urdf/limits.h>
12 
13 TEST(TesseractURDFUnit, parse_limits) // NOLINT
14 {
15  {
16  std::string str = R"(<limit lower="1" upper="2" effort="3" velocity="4" extra="0 0 0"/>)";
18  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
20  EXPECT_NEAR(elem->lower, 1, 1e-8);
21  EXPECT_NEAR(elem->upper, 2, 1e-8);
22  EXPECT_NEAR(elem->effort, 3, 1e-8);
23  EXPECT_NEAR(elem->velocity, 4, 1e-8);
24  }
25 
26  {
27  std::string str = R"(<limit upper="2" effort="3" velocity="4"/>)";
29  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
31  EXPECT_NEAR(elem->lower, 0, 1e-8);
32  EXPECT_NEAR(elem->upper, 2, 1e-8);
33  EXPECT_NEAR(elem->effort, 3, 1e-8);
34  EXPECT_NEAR(elem->velocity, 4, 1e-8);
35  }
36 
37  {
38  std::string str = R"(<limit lower="1" effort="3" velocity="4"/>)";
40  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
42  EXPECT_NEAR(elem->lower, 1, 1e-8);
43  EXPECT_NEAR(elem->upper, 0, 1e-8);
44  EXPECT_NEAR(elem->effort, 3, 1e-8);
45  EXPECT_NEAR(elem->velocity, 4, 1e-8);
46  }
47 
48  {
49  std::string str = R"(<limit effort="3" velocity="4"/>)";
51  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
53  EXPECT_NEAR(elem->lower, 0, 1e-8);
54  EXPECT_NEAR(elem->upper, 0, 1e-8);
55  EXPECT_NEAR(elem->effort, 3, 1e-8);
56  EXPECT_NEAR(elem->velocity, 4, 1e-8);
57  }
58 
59  {
60  std::string str = R"(<limit effort="3" velocity="4" acceleration="2"/>)";
62  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
64  EXPECT_NEAR(elem->lower, 0, 1e-8);
65  EXPECT_NEAR(elem->upper, 0, 1e-8);
66  EXPECT_NEAR(elem->effort, 3, 1e-8);
67  EXPECT_NEAR(elem->velocity, 4, 1e-8);
68  EXPECT_NEAR(elem->acceleration, 2, 1e-8);
69  }
70 
71  {
72  std::string str = R"(<limit effort="3" velocity="4" jerk="2"/>)";
74  EXPECT_TRUE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
76  EXPECT_NEAR(elem->lower, 0, 1e-8);
77  EXPECT_NEAR(elem->upper, 0, 1e-8);
78  EXPECT_NEAR(elem->effort, 3, 1e-8);
79  EXPECT_NEAR(elem->velocity, 4, 1e-8);
80  EXPECT_NEAR(elem->jerk, 2, 1e-8);
81  }
82 
83  {
84  std::string str = R"(<limit lower="a" upper="2" effort="3" velocity="4"/>)";
86  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
88  }
89 
90  {
91  std::string str = R"(<limit lower="1" upper="a" effort="3" velocity="4"/>)";
93  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
95  }
96 
97  {
98  std::string str = R"(<limit lower="1" upper="2" effort="a" velocity="4"/>)";
100  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
102  }
103 
104  {
105  std::string str = R"(<limit lower="1" upper="2" effort="3" velocity="a"/>)";
107  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
109  }
110 
111  {
112  std::string str = R"(<limit lower="1" upper="2" effort="3" velocity="4" acceleration="a"/>)";
114  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
116  }
117 
118  {
119  std::string str = R"(<limit lower="1" upper="2" effort="3" velocity="4" jerk="a"/>)";
121  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
123  }
124 
125  {
126  std::string str = R"(<limit velocity="4"/>)";
128  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
130  }
131 
132  {
133  std::string str = R"(<limit acceleration="2"/>)";
135  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
137  }
138 
139  {
140  std::string str = R"(<limit effort="3"/>)";
142  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
144  }
145 
146  {
147  std::string str = "<limit />";
149  EXPECT_FALSE(runTest<tesseract_scene_graph::JointLimits::Ptr>(
151  }
152 }
153 
154 TEST(TesseractURDFUnit, write_limits) // NOLINT
155 {
156  {
157  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
158  std::string text;
159  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
160  EXPECT_TRUE(text == R"(<limit effort="0" velocity="0"/>)");
161  }
162 
163  {
164  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
165  limits->lower = 1.0;
166  limits->upper = 2.0;
167  limits->effort = 3.0;
168  limits->velocity = 4.0;
169  limits->acceleration = 2.0;
170  std::string text;
171  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
172  EXPECT_EQ(text, R"(<limit lower="1" upper="2" effort="3" velocity="4"/>)");
173  }
174 
175  {
176  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
177  limits->lower = 1.0;
178  limits->upper = 2.0;
179  limits->effort = 3.0;
180  limits->velocity = 4.0;
181  limits->acceleration = 3.0;
182  std::string text;
183  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
184  EXPECT_EQ(text, R"(<limit lower="1" upper="2" effort="3" velocity="4" acceleration="3"/>)");
185  }
186 
187  {
188  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
189  limits->lower = 1.0;
190  limits->upper = 2.0;
191  limits->effort = 3.0;
192  limits->velocity = 4.0;
193  limits->jerk = 0.0;
194  std::string text;
195  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
196  EXPECT_EQ(text, R"(<limit lower="1" upper="2" effort="3" velocity="4"/>)");
197  }
198 
199  {
200  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
201  limits->lower = 1.0;
202  limits->upper = 2.0;
203  limits->effort = 3.0;
204  limits->velocity = 4.0;
205  limits->jerk = 1000.0;
206  std::string text;
207  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
208  EXPECT_EQ(text, R"(<limit lower="1" upper="2" effort="3" velocity="4"/>)");
209  }
210 
211  {
212  tesseract_scene_graph::JointLimits::Ptr limits = std::make_shared<tesseract_scene_graph::JointLimits>();
213  limits->lower = 1.0;
214  limits->upper = 2.0;
215  limits->effort = 3.0;
216  limits->velocity = 4.0;
217  limits->jerk = 500.0;
218  std::string text;
219  EXPECT_EQ(0, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
220  EXPECT_EQ(text, R"(<limit lower="1" upper="2" effort="3" velocity="4" jerk="500"/>)");
221  }
222 
223  {
225  std::string text;
226  EXPECT_EQ(1, writeTest<tesseract_scene_graph::JointLimits::Ptr>(limits, &tesseract_urdf::writeLimits, text));
227  EXPECT_EQ(text, "");
228  }
229 }
TEST
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_limits)
Definition: tesseract_urdf_limits_unit.cpp:13
tesseract_urdf::writeLimits
tinyxml2::XMLElement * writeLimits(const std::shared_ptr< const tesseract_scene_graph::JointLimits > &limits, tinyxml2::XMLDocument &doc)
Definition: limits.cpp:74
tesseract_scene_graph::JointLimits::Ptr
std::shared_ptr< JointLimits > Ptr
joint.h
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
EXPECT_TRUE
#define EXPECT_TRUE(args)
limits.h
Parse limits from xml string.
tesseract_urdf_common_unit.h
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
tesseract_urdf::parseLimits
std::shared_ptr< tesseract_scene_graph::JointLimits > parseLimits(const tinyxml2::XMLElement *xml_element)
Parse xml element limits.
Definition: limits.cpp:41
TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_urdf::LIMITS_ELEMENT_NAME
static constexpr std::string_view LIMITS_ELEMENT_NAME
Definition: limits.h:45
macros.h
EXPECT_EQ
#define EXPECT_EQ(a, b)
EXPECT_FALSE
#define EXPECT_FALSE(args)


tesseract_urdf
Author(s): Levi Armstrong
autogenerated on Thu Apr 24 2025 03:10:44