File: joint_axis_frame.cc

package info (click to toggle)
sdformat 4.2.0-1
  • links: PTS, VCS
  • area: main
  • in suites: stretch
  • size: 4,492 kB
  • ctags: 6,349
  • sloc: cpp: 26,300; python: 1,633; ruby: 217; ansic: 79; sh: 77; makefile: 18
file content (76 lines) | stat: -rw-r--r-- 2,382 bytes parent folder | download
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
/*
 * Copyright 2014 Open Source Robotics Foundation
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 *     http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *
*/

#include <gtest/gtest.h>
#include <string>
#include "sdf/sdf.hh"

#include "test_config.h"

std::string get_sdf_string(std::string _version)
{
  std::ostringstream stream;
  stream
    << "<sdf version='" << _version << "'>"
    << "<model name='model'>"
    << "  <link name='parent'/>"
    << "  <link name='child'/>"
    << "  <joint name='joint' type='revolute'>"
    << "    <parent>parent</parent>"
    << "    <child>child</child>"
    << "    <axis>"
    << "      <xyz>1 0 0</xyz>"
    << "    </axis>"
    << "  </joint>"
    << "</model>"
    << "</sdf>";
  return stream.str();
}

////////////////////////////////////////
// sdf model, version 1.4, use_parent_model_frame tag missing
// expect tag to be inserted with value true
TEST(JointAxisFrame, Version_1_4_missing)
{
  sdf::SDFPtr model(new sdf::SDF());
  sdf::init(model);
  ASSERT_TRUE(sdf::readString(get_sdf_string("1.4"), model));

  sdf::ElementPtr joint = model->Root()->GetElement(
    "model")->GetElement("joint");
  sdf::ElementPtr axis = joint->GetElement("axis");

  axis->PrintValues("");
  EXPECT_TRUE(axis->HasElement("use_parent_model_frame"));
  EXPECT_TRUE(axis->Get<bool>("use_parent_model_frame"));
}

////////////////////////////////////////
// sdf model, version 1.5, use_parent_model_frame tag missing
// expect tag to be inserted with value false
TEST(JointAxisFrame, Version_1_5_missing)
{
  sdf::SDFPtr model(new sdf::SDF());
  sdf::init(model);
  ASSERT_TRUE(sdf::readString(get_sdf_string("1.5"), model));

  sdf::ElementPtr joint = model->Root()->GetElement(
    "model")->GetElement("joint");
  sdf::ElementPtr axis = joint->GetElement("axis");
  EXPECT_TRUE(axis->HasElement("use_parent_model_frame"));
  EXPECT_FALSE(axis->Get<bool>("use_parent_model_frame"));
}