File: test_IkFast.cpp

package info (click to toggle)
dart 6.12.1%2Bdfsg4-12
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 57,000 kB
  • sloc: cpp: 269,461; python: 3,911; xml: 1,273; sh: 404; makefile: 30
file content (169 lines) | stat: -rw-r--r-- 6,349 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
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
156
157
158
159
160
161
162
163
164
165
166
167
168
169
/*
 * Copyright (c) 2011-2021, The DART development contributors
 * All rights reserved.
 *
 * The list of contributors can be found at:
 *   https://github.com/dartsim/dart/blob/master/LICENSE
 *
 * This file is provided under the following "BSD-style" License:
 *   Redistribution and use in source and binary forms, with or
 *   without modification, are permitted provided that the following
 *   conditions are met:
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
 *   CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
 *   INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
 *   MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
 *   DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
 *   CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
 *   USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 *   AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *   LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *   ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *   POSSIBILITY OF SUCH DAMAGE.
 */

#include <sstream>

#include <dart/dart.hpp>
#include <dart/utils/urdf/urdf.hpp>
#include <gtest/gtest.h>

#include "TestHelpers.hpp"

using namespace dart;

//==============================================================================
TEST(IkFast, WrapCyclicSolution)
{
  const auto pi = math::constantsd::pi();

  double sol;

  // Invalid bounds (lb > ub)
  EXPECT_FALSE(dynamics::wrapCyclicSolution(0, 10, -10, sol));

  // Current value is in the lmits, but solution is lesser than lower limit.
  // Expect valid solution that is the cloest to the current value.
  sol = -3 * pi;
  EXPECT_TRUE(dynamics::wrapCyclicSolution(-pi / 2, -pi, +pi, sol));
  EXPECT_DOUBLE_EQ(sol, -pi);
  sol = -3 * pi;
  EXPECT_TRUE(
      dynamics::wrapCyclicSolution(-pi / 2, -(3.0 / 4.0) * pi, +pi, sol));
  EXPECT_DOUBLE_EQ(sol, +pi);
  sol = -3 * pi;
  EXPECT_FALSE(
      dynamics::wrapCyclicSolution(-pi / 2, -0.9 * pi, +0.9 * pi, sol));

  // Current value is in the lmits, but solution is greater than upper limit.
  // Expect valid solution that is the cloest to the current value.
  sol = -3 * pi;
  EXPECT_TRUE(dynamics::wrapCyclicSolution(+pi / 2, -pi, +pi, sol));
  EXPECT_DOUBLE_EQ(sol, +pi);
  sol = -3 * pi;
  EXPECT_TRUE(
      dynamics::wrapCyclicSolution(+pi / 2, -pi, +(3.0 / 4.0) * pi, sol));
  EXPECT_DOUBLE_EQ(sol, -pi);
  sol = -3 * pi;
  EXPECT_FALSE(
      dynamics::wrapCyclicSolution(+pi / 2, -0.9 * pi, +0.9 * pi, sol));

  // Both current value and solution are lesser than lower limit.
  // Expect least valid solution.
  sol = -9 * pi;
  EXPECT_TRUE(dynamics::wrapCyclicSolution(-5 * pi, -4 * pi, +4 * pi, sol));
  EXPECT_DOUBLE_EQ(sol, -3 * pi);
  sol = -9 * pi;
  EXPECT_FALSE(dynamics::wrapCyclicSolution(-5 * pi, -4 * pi, -3.1 * pi, sol));

  // Both current value and solution are greater than upper limit.
  // Expect greatest valid solution.
  sol = +9 * pi;
  EXPECT_TRUE(dynamics::wrapCyclicSolution(+5 * pi, -4 * pi, +4 * pi, sol));
  EXPECT_DOUBLE_EQ(sol, +3 * pi);
  sol = +9 * pi;
  EXPECT_FALSE(dynamics::wrapCyclicSolution(+5 * pi, +3.1 * pi, +4 * pi, sol));
}

//==============================================================================
TEST(IkFast, FailedToLoadSharedLibrary)
{
  auto skel = dynamics::Skeleton::create();
  ASSERT_NE(skel, nullptr);

  auto bodyNode
      = skel->createJointAndBodyNodePair<dynamics::FreeJoint>().second;

  auto ee = bodyNode->createEndEffector("ee");
  ASSERT_NE(ee, nullptr);
  auto ik = ee->createIK();
  ASSERT_NE(ik, nullptr);
  auto ikfast = ik->setGradientMethod<dynamics::SharedLibraryIkFast>(
      "doesn't exist", std::vector<std::size_t>(), std::vector<std::size_t>());
  EXPECT_EQ(ikfast.isConfigured(), false);
}

//==============================================================================
TEST(IkFast, LoadWamArmIk)
{
  utils::DartLoader urdfParser;
  urdfParser.addPackageDirectory(
      "herb_description", DART_DATA_PATH "/urdf/wam");
  auto wam = urdfParser.parseSkeleton(DART_DATA_PATH "/urdf/wam/wam.urdf");
  ASSERT_NE(wam, nullptr);

  auto wam7 = wam->getBodyNode("/wam7");
  ASSERT_NE(wam7, nullptr);
  auto ee = wam7->createEndEffector("ee");
  auto ik = ee->createIK();
  auto targetFrame
      = dynamics::SimpleFrame::createShared(dynamics::Frame::World());
  targetFrame->setRotation(Eigen::Matrix3d::Identity());

  ik->setTarget(targetFrame);
  ik->setHierarchyLevel(1);
  std::stringstream ss;
  ss << DART_SHARED_LIB_PREFIX << "GeneratedWamIkFast";
  ss << "." << DART_SHARED_LIB_EXTENSION;
  std::string libName = ss.str();
  std::vector<std::size_t> ikFastDofs{0, 1, 3, 4, 5, 6};
  std::vector<std::size_t> ikFastFreeDofs{2};
  ik->setGradientMethod<dynamics::SharedLibraryIkFast>(
      libName, ikFastDofs, ikFastFreeDofs);
  auto analytical = ik->getAnalytical();
  ASSERT_NE(analytical, nullptr);
  EXPECT_EQ(analytical->getDofs().size(), 6);

  auto ikfast = dynamic_cast<dynamics::SharedLibraryIkFast*>(analytical);
  ASSERT_NE(ikfast, nullptr);
  EXPECT_EQ(ikfast->getNumJoints2(), 7);
  EXPECT_EQ(ikfast->getNumFreeParameters2(), 1);
  EXPECT_EQ(ikfast->getIkType2(), dynamics::IkFast::IkType::TRANSFORM_6D);
  EXPECT_EQ(ikfast->getIkFastVersion2(), "71");

  targetFrame->setTranslation(Eigen::Vector3d(0, 0, 0.5));
  auto solutions = ikfast->getSolutions(targetFrame->getTransform());
  EXPECT_TRUE(!solutions.empty());

  const auto dofs = ikfast->getDofs();

  for (const auto& solution : solutions)
  {
    ASSERT_EQ(solution.mConfig.size(), 6);

    if (solution.mValidity != InverseKinematics::Analytical::VALID)
      continue;

    wam->setPositions(dofs, solution.mConfig);
    Eigen::Isometry3d newTf = ee->getTransform();
    EXPECT_TRUE(equals(targetFrame->getTransform(), newTf, 1e-2));
  }
}