1 /*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33 #include <gtest/gtest.h>
34
35 #include "dart/dynamics/SimpleFrame.hpp"
36 #include "dart/math/Helpers.hpp"
37 #include "dart/math/Random.hpp"
38
39 #include "TestHelpers.hpp"
40
41 using namespace dart;
42 using namespace dynamics;
43
44 //==============================================================================
createFloor()45 dynamics::SkeletonPtr createFloor()
46 {
47 auto floor = dynamics::Skeleton::create("floor");
48
49 // Give the floor a body
50 auto body
51 = floor->createJointAndBodyNodePair<dynamics::WeldJoint>(nullptr).second;
52
53 // Give the body a shape
54 double floorWidth = 10.0;
55 double floorHeight = 0.01;
56 auto box = std::make_shared<dynamics::BoxShape>(
57 Eigen::Vector3d(floorWidth, floorWidth, floorHeight));
58 auto* shapeNode = body->createShapeNodeWith<
59 dynamics::VisualAspect,
60 dynamics::CollisionAspect,
61 dynamics::DynamicsAspect>(box);
62 shapeNode->getVisualAspect()->setColor(dart::Color::LightGray());
63
64 // Put the body into position
65 Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();
66 tf.translation() = Eigen::Vector3d(0.0, 0.0, -0.5 - floorHeight / 2.0);
67 body->getParentJoint()->setTransformFromParentBodyNode(tf);
68
69 return floor;
70 }
71
72 //==============================================================================
TEST(Friction,FrictionPerShapeNode)73 TEST(Friction, FrictionPerShapeNode)
74 {
75 auto skeleton1
76 = createBox(Eigen::Vector3d(0.3, 0.3, 0.3), Eigen::Vector3d(-0.5, 0, 0));
77 skeleton1->setName("Skeleton1");
78 auto skeleton2
79 = createBox(Eigen::Vector3d(0.3, 0.3, 0.3), Eigen::Vector3d(+0.5, 0, 0));
80 skeleton2->setName("Skeleton2");
81 auto skeleton3 = createBox(
82 Eigen::Vector3d(0.3, 0.3, 0.3),
83 Eigen::Vector3d(+1.5, 0, 0),
84 Eigen::Vector3d(0, 0, 0.7853981633974483));
85 skeleton3->setName("Skeleton3");
86 auto skeleton4 = createBox(
87 Eigen::Vector3d(0.3, 0.3, 0.3),
88 Eigen::Vector3d(-1.5, 0, 0),
89 Eigen::Vector3d(0, 0, 0.7853981633974483));
90 skeleton4->setName("Skeleton4");
91
92 auto body1 = skeleton1->getRootBodyNode();
93 // default friction values
94 EXPECT_DOUBLE_EQ(
95 1.0, body1->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
96 EXPECT_DOUBLE_EQ(
97 1.0,
98 body1->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
99 EXPECT_DOUBLE_EQ(
100 1.0,
101 body1->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
102
103 auto body2 = skeleton2->getRootBodyNode();
104 // default friction values
105 EXPECT_DOUBLE_EQ(
106 1.0, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
107 EXPECT_DOUBLE_EQ(
108 1.0,
109 body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
110 EXPECT_DOUBLE_EQ(
111 1.0,
112 body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
113 // test setting primary friction
114 body2->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.5);
115 EXPECT_DOUBLE_EQ(
116 0.75, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
117 EXPECT_DOUBLE_EQ(
118 0.5,
119 body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
120 EXPECT_DOUBLE_EQ(
121 1.0,
122 body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
123 // test setting secondary friction
124 body2->getShapeNode(0)->getDynamicsAspect()->setSecondaryFrictionCoeff(0.25);
125 EXPECT_DOUBLE_EQ(
126 0.375, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
127 EXPECT_DOUBLE_EQ(
128 0.5,
129 body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
130 EXPECT_DOUBLE_EQ(
131 0.25,
132 body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
133 // set all friction coeffs to 0.0
134 body2->getShapeNode(0)->getDynamicsAspect()->setFrictionCoeff(0.0);
135 EXPECT_DOUBLE_EQ(
136 0.0, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
137 EXPECT_DOUBLE_EQ(
138 0.0,
139 body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
140 EXPECT_DOUBLE_EQ(
141 0.0,
142 body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
143
144 auto body3 = skeleton3->getRootBodyNode();
145 // default friction values
146 EXPECT_DOUBLE_EQ(
147 1.0, body3->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
148 EXPECT_DOUBLE_EQ(
149 1.0,
150 body3->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
151 EXPECT_DOUBLE_EQ(
152 1.0,
153 body3->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
154 EXPECT_DOUBLE_EQ(
155 0.0,
156 body3->getShapeNode(0)
157 ->getDynamicsAspect()
158 ->getFirstFrictionDirection()
159 .squaredNorm());
160 EXPECT_EQ(
161 nullptr,
162 body3->getShapeNode(0)
163 ->getDynamicsAspect()
164 ->getFirstFrictionDirectionFrame());
165 // this body is rotated by 45 degrees, so set friction direction in body frame
166 // along Y axis so that gravity pushes it in x and y
167 body3->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.0);
168 body3->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirection(
169 Eigen::Vector3d(0, 1, 0));
170 // check friction values
171 EXPECT_DOUBLE_EQ(
172 0.5, body3->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
173 EXPECT_DOUBLE_EQ(
174 0.0,
175 body3->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
176 EXPECT_DOUBLE_EQ(
177 1.0,
178 body3->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
179 EXPECT_DOUBLE_EQ(
180 1.0,
181 body3->getShapeNode(0)
182 ->getDynamicsAspect()
183 ->getFirstFrictionDirection()
184 .squaredNorm());
185 EXPECT_EQ(
186 nullptr,
187 body3->getShapeNode(0)
188 ->getDynamicsAspect()
189 ->getFirstFrictionDirectionFrame());
190
191 auto body4 = skeleton4->getRootBodyNode();
192 // default friction values
193 EXPECT_DOUBLE_EQ(
194 1.0, body4->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
195 EXPECT_DOUBLE_EQ(
196 1.0,
197 body4->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
198 EXPECT_DOUBLE_EQ(
199 1.0,
200 body4->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
201 EXPECT_DOUBLE_EQ(
202 0.0,
203 body4->getShapeNode(0)
204 ->getDynamicsAspect()
205 ->getFirstFrictionDirection()
206 .squaredNorm());
207 EXPECT_EQ(
208 nullptr,
209 body4->getShapeNode(0)
210 ->getDynamicsAspect()
211 ->getFirstFrictionDirectionFrame());
212 // this body is rotated by 45 degrees, but set friction direction according to
213 // world frame so that the body orientation doesn't matter. thus a diagonal
214 // axis is needed to push it in x and y
215 body4->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.0);
216 body4->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirectionFrame(
217 Frame::World());
218 body4->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirection(
219 Eigen::Vector3d(0.5 * std::sqrt(2), 0.5 * std::sqrt(2), 0));
220 // check friction values
221 EXPECT_DOUBLE_EQ(
222 0.5, body4->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
223 EXPECT_DOUBLE_EQ(
224 0.0,
225 body4->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
226 EXPECT_DOUBLE_EQ(
227 1.0,
228 body4->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
229 EXPECT_DOUBLE_EQ(
230 1.0,
231 body4->getShapeNode(0)
232 ->getDynamicsAspect()
233 ->getFirstFrictionDirection()
234 .squaredNorm());
235 EXPECT_EQ(
236 Frame::World(),
237 body4->getShapeNode(0)
238 ->getDynamicsAspect()
239 ->getFirstFrictionDirectionFrame());
240
241 // Create a world and add the rigid body
242 auto world = simulation::World::create();
243 EXPECT_TRUE(equals(world->getGravity(), ::Eigen::Vector3d(0, 0, -9.81)));
244 world->setGravity(Eigen::Vector3d(0.0, -5.0, -9.81));
245 EXPECT_TRUE(equals(world->getGravity(), ::Eigen::Vector3d(0.0, -5.0, -9.81)));
246
247 world->addSkeleton(createFloor());
248 world->addSkeleton(skeleton1);
249 world->addSkeleton(skeleton2);
250 world->addSkeleton(skeleton3);
251 world->addSkeleton(skeleton4);
252
253 const auto numSteps = 500;
254 for (auto i = 0u; i < numSteps; ++i)
255 {
256 world->step();
257
258 // Wait until the first box settle-in on the ground
259 if (i > 300)
260 {
261 const auto x1 = body1->getTransform().translation()[0];
262 const auto y1 = body1->getTransform().translation()[1];
263 EXPECT_NEAR(x1, -0.5, 0.00001);
264 EXPECT_NEAR(y1, -0.17889, 0.001);
265
266 // The second box still moves even after landing on the ground because its
267 // friction is zero.
268 const auto x2 = body2->getTransform().translation()[0];
269 const auto y2 = body2->getTransform().translation()[1];
270 EXPECT_NEAR(x2, 0.5, 0.00001);
271 EXPECT_LE(y2, -0.17889);
272
273 // The third box still moves even after landing on the ground because its
274 // friction is zero along the first friction direction.
275 const auto x3 = body3->getTransform().translation()[0];
276 const auto y3 = body3->getTransform().translation()[1];
277 EXPECT_GE(x3, 1.5249);
278 EXPECT_LE(y3, -0.20382);
279
280 // The fourth box still moves even after landing on the ground because its
281 // friction is zero along the first friction direction.
282 const auto x4 = body4->getTransform().translation()[0];
283 const auto y4 = body4->getTransform().translation()[1];
284 EXPECT_LE(x4, -1.5249);
285 EXPECT_LE(y4, -0.20382);
286 }
287 }
288 }
289