File: urdf_joint_parameters.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 (68 lines) | stat: -rw-r--r-- 2,044 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
/*
 * 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 <map>
#include "sdf/sdf.hh"

#include "test_config.h"

const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH)
  + "/test/integration/urdf_joint_parameters.urdf";

/////////////////////////////////////////////////
TEST(SDFParser, JointAxisParameters)
{
  sdf::SDFPtr robot(new sdf::SDF());
  sdf::init(robot);
  ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot));

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

  ASSERT_TRUE(model->HasElement("joint"));
  unsigned int bitmask = 0;
  for (sdf::ElementPtr joint = model->GetElement("joint"); joint;
       joint = joint->GetNextElement("joint"))
  {
    std::string jointName = joint->Get<std::string>("name");

    double value = -1.0;
    if (jointName == "jointw0")
    {
      bitmask |= 0x1;
      value = 0.0;
    }
    else if (jointName == "joint01")
    {
      bitmask |= 0x2;
      value = 1.0;
    }
    else
    {
      continue;
    }
    ASSERT_TRUE(joint->HasElement("axis"));
    sdf::ElementPtr axis = joint->GetElement("axis");
    ASSERT_TRUE(axis->HasElement("dynamics"));
    sdf::ElementPtr dynamics = axis->GetElement("dynamics");
    ASSERT_TRUE(dynamics->HasElement("damping"));
    ASSERT_TRUE(dynamics->HasElement("friction"));
    EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("damping"));
    EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("friction"));
  }
  EXPECT_EQ(bitmask, 0x3u);
}