File: urdf_version_test.cpp

package info (click to toggle)
urdfdom 4.0.0-4
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 380 kB
  • sloc: cpp: 2,541; sh: 32; xml: 29; makefile: 8
file content (155 lines) | stat: -rw-r--r-- 4,660 bytes parent folder | download | duplicates (3)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
#include <iostream>
#include <string>

#include <gtest/gtest.h>

#include <urdf_parser/urdf_parser.h>

#define EXPECT_THROW_OF_TYPE(type, statement, msg)                         \
  do {                                                                     \
    try {                                                                  \
      statement;                                                           \
    } catch (const type & err) {                                           \
      if (std::string(err.what()).find(msg) == std::string::npos) {        \
        FAIL() << "Expected error msg containing:" << std::endl            \
               << msg << std::endl                                         \
               << "Saw error msg:" << std::endl                            \
               << err.what() << std::endl;                                 \
      }                                                                    \
    } catch (const std::exception & err) {                                 \
      FAIL() << "Expected " #type << std::endl                             \
             << "Saw exception type: " << typeid(err).name() << std::endl; \
    }                                                                      \
  } while (0)

#define EXPECT_RUNTIME_THROW(st, msg) \
  EXPECT_THROW_OF_TYPE(std::runtime_error, st, msg)


TEST(URDF_VERSION, test_version_wrong_type)
{
  std::string test_str =
    "<robot name=\"test\" version=\"foo\">"
    "</robot>";

  urdf::ModelInterfaceSharedPtr urdf = urdf::parseURDF(test_str);

  EXPECT_EQ(urdf, nullptr);
}

TEST(URDF_VERSION, test_version_unsupported_version)
{
  std::string test_str =
    "<robot name=\"test\" version=\"2\">"
    "</robot>";

  urdf::ModelInterfaceSharedPtr urdf = urdf::parseURDF(test_str);

  EXPECT_EQ(urdf, nullptr);
}

TEST(URDF_VERSION, test_version_not_specified)
{
  std::string test_str =
    "<robot name=\"test\">"
    "  <link name=\"l1\"/>"
    "</robot>";

  urdf::ModelInterfaceSharedPtr urdf = urdf::parseURDF(test_str);

  EXPECT_NE(urdf, nullptr);
}

TEST(URDF_VERSION, test_version_one_int)
{
  std::string test_str =
    "<robot name=\"test\" version=\"1\">"
    "  <link name=\"l1\"/>"
    "</robot>";

  urdf::ModelInterfaceSharedPtr urdf = urdf::parseURDF(test_str);

  EXPECT_EQ(urdf, nullptr);
}

TEST(URDF_VERSION, test_version_one_float)
{
  std::string test_str =
    "<robot name=\"test\" version=\"1.0\">"
    "  <link name=\"l1\"/>"
    "</robot>";

  urdf::ModelInterfaceSharedPtr urdf = urdf::parseURDF(test_str);

  EXPECT_NE(urdf, nullptr);
}

TEST(URDF_VERSION_CLASS, test_null_ptr)
{
  urdf_export_helpers::URDFVersion vers1(nullptr);

  EXPECT_EQ(vers1.getMajor(), 1u);
  EXPECT_EQ(vers1.getMinor(), 0u);
}

TEST(URDF_VERSION_CLASS, test_correct_string)
{
  urdf_export_helpers::URDFVersion vers2("1.0");

  EXPECT_EQ(vers2.getMajor(), 1u);
  EXPECT_EQ(vers2.getMinor(), 0u);
}

TEST(URDF_VERSION_CLASS, test_too_many_dots)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("1.0.0"),
                       "The version attribute should be in the form 'x.y'");
}

TEST(URDF_VERSION_CLASS, test_not_enough_numbers)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("1."),
                       "The version attribute should be in the form 'x.y'");
}

TEST(URDF_VERSION_CLASS, test_no_major_number)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2(".1"),
                       "One of the fields of the version attribute is blank");
}

TEST(URDF_VERSION_CLASS, test_negative_major_number)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("-1.0"),
                       "Version number must be positive");
}

TEST(URDF_VERSION_CLASS, test_negative_minor_number)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("1.-1"),
                       "Version number must be positive");
}

TEST(URDF_VERSION_CLASS, test_no_numbers)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("abc"),
                       "The version attribute should be in the form 'x.y'");
}

TEST(URDF_VERSION_CLASS, test_dots_no_numbers)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("a.c"),
                       "Version attribute is not an integer");
}

TEST(URDF_VERSION_CLASS, test_dots_one_number)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("1.c"),
                       "Version attribute is not an integer");
}

TEST(URDF_VERSION_CLASS, test_trailing_junk)
{
  EXPECT_RUNTIME_THROW(urdf_export_helpers::URDFVersion vers2("1.0~pre6"),
                       "Extra characters after the version number");
}