File: sdf_custom.cc

package info (click to toggle)
sdformat 9.3.0%2Bds-3
  • links: PTS, VCS
  • area: main
  • in suites: bullseye
  • size: 5,708 kB
  • sloc: cpp: 42,166; python: 1,618; javascript: 704; ruby: 368; sh: 81; ansic: 37; makefile: 16
file content (85 lines) | stat: -rw-r--r-- 3,006 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
77
78
79
80
81
82
83
84
85
/*
 * Copyright 2019 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 <string>

#include <gtest/gtest.h>

#include "sdf/sdf.hh"

#include "test_config.h"

const std::string SDF_TEST_FILE =
  sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "integration",
                          "custom_elems_attrs.sdf");

/////////////////////////////////////////////////
TEST(SDFParser, CustomElements)
{
  sdf::Root root;
  EXPECT_TRUE(root.Load(SDF_TEST_FILE).empty());

  const sdf::World *world = root.WorldByIndex(0);

  std::string worldName = world->Name();
  EXPECT_EQ("W", worldName);

  // Use of sdf::World::Element() to obtain an sdf::ElementPtr object
  sdf::ElementPtr worldElement = world->Element();

  // Use of sdf::ElementPtr::GetAttribute()
  sdf::ParamPtr typeParam = worldElement->GetAttribute("mysim:type");
  std::string simType;
  // Use of sdf::ParamPtr::Get<T>()
  typeParam->Get<std::string>(simType);
  EXPECT_EQ("2d", simType);

  const sdf::Model *model = world->ModelByIndex(0);

  const sdf::Link *link1 = model->LinkByIndex(0);
  // Use of sdf::Link::Element() to obtain an sdf::ElementPtr object
  sdf::ElementPtr link1Element = link1->Element();

  // Use of sdf::ElementPtr::Get<T>() to obtain the value of an attribute
  auto customAttrStr = link1Element->Get<std::string>("mysim:custom_attr_str");
  EXPECT_EQ("A", customAttrStr);

  auto customAttrInt = link1Element->Get<int>("mysim:custom_attr_int");
  EXPECT_EQ(5, customAttrInt);

  // Use of sdf::Model::Element() to obtain an sdf::ElementPtr object
  sdf::ElementPtr modelElement = model->Element();

  sdf::ElementPtr transmission = modelElement->GetElement("mysim:transmission");
  auto transmissionName = transmission->Get<std::string>("name");
  EXPECT_EQ("simple_trans", transmissionName);

  auto transmissionType = transmission->Get<std::string>("mysim:type");
  EXPECT_EQ("transmission_interface/SimpleTransmission", transmissionType);

  sdf::ElementPtr tranJointElement = transmission->GetElement("mysim:joint");
  auto tranJointName = tranJointElement->Get<std::string>("name");
  EXPECT_EQ("J1", tranJointName);

  sdf::ElementPtr transHwInterfaceElement =
      tranJointElement->GetElement("mysim:hardwareInterface");

  // Use of sdf::ElementPtr::Get<T>() to obtain the value of a child element
  auto tranHwInterface =
      tranJointElement->Get<std::string>("mysim:hardwareInterface");
  EXPECT_EQ("EffortJointInterface", tranHwInterface);
}