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 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288
|
/*
* Copyright (c) 2011-2022, 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 <gtest/gtest.h>
#include "dart/dynamics/SimpleFrame.hpp"
#include "dart/math/Helpers.hpp"
#include "dart/math/Random.hpp"
#include "TestHelpers.hpp"
using namespace dart;
using namespace dynamics;
//==============================================================================
dynamics::SkeletonPtr createFloor()
{
auto floor = dynamics::Skeleton::create("floor");
// Give the floor a body
auto body
= floor->createJointAndBodyNodePair<dynamics::WeldJoint>(nullptr).second;
// Give the body a shape
double floorWidth = 10.0;
double floorHeight = 0.01;
auto box = std::make_shared<dynamics::BoxShape>(
Eigen::Vector3d(floorWidth, floorWidth, floorHeight));
auto* shapeNode = body->createShapeNodeWith<
dynamics::VisualAspect,
dynamics::CollisionAspect,
dynamics::DynamicsAspect>(box);
shapeNode->getVisualAspect()->setColor(dart::Color::LightGray());
// Put the body into position
Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();
tf.translation() = Eigen::Vector3d(0.0, 0.0, -0.5 - floorHeight / 2.0);
body->getParentJoint()->setTransformFromParentBodyNode(tf);
return floor;
}
//==============================================================================
TEST(Friction, FrictionPerShapeNode)
{
auto skeleton1
= createBox(Eigen::Vector3d(0.3, 0.3, 0.3), Eigen::Vector3d(-0.5, 0, 0));
skeleton1->setName("Skeleton1");
auto skeleton2
= createBox(Eigen::Vector3d(0.3, 0.3, 0.3), Eigen::Vector3d(+0.5, 0, 0));
skeleton2->setName("Skeleton2");
auto skeleton3 = createBox(
Eigen::Vector3d(0.3, 0.3, 0.3),
Eigen::Vector3d(+1.5, 0, 0),
Eigen::Vector3d(0, 0, 0.7853981633974483));
skeleton3->setName("Skeleton3");
auto skeleton4 = createBox(
Eigen::Vector3d(0.3, 0.3, 0.3),
Eigen::Vector3d(-1.5, 0, 0),
Eigen::Vector3d(0, 0, 0.7853981633974483));
skeleton4->setName("Skeleton4");
auto body1 = skeleton1->getRootBodyNode();
// default friction values
EXPECT_DOUBLE_EQ(
1.0, body1->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body1->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body1->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
auto body2 = skeleton2->getRootBodyNode();
// default friction values
EXPECT_DOUBLE_EQ(
1.0, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
// test setting primary friction
body2->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.5);
EXPECT_DOUBLE_EQ(
0.75, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.5,
body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
// test setting secondary friction
body2->getShapeNode(0)->getDynamicsAspect()->setSecondaryFrictionCoeff(0.25);
EXPECT_DOUBLE_EQ(
0.375, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.5,
body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.25,
body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
// set all friction coeffs to 0.0
body2->getShapeNode(0)->getDynamicsAspect()->setFrictionCoeff(0.0);
EXPECT_DOUBLE_EQ(
0.0, body2->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body2->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body2->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
auto body3 = skeleton3->getRootBodyNode();
// default friction values
EXPECT_DOUBLE_EQ(
1.0, body3->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body3->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body3->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body3->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirection()
.squaredNorm());
EXPECT_EQ(
nullptr,
body3->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirectionFrame());
// this body is rotated by 45 degrees, so set friction direction in body frame
// along Y axis so that gravity pushes it in x and y
body3->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.0);
body3->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirection(
Eigen::Vector3d(0, 1, 0));
// check friction values
EXPECT_DOUBLE_EQ(
0.5, body3->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body3->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body3->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body3->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirection()
.squaredNorm());
EXPECT_EQ(
nullptr,
body3->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirectionFrame());
auto body4 = skeleton4->getRootBodyNode();
// default friction values
EXPECT_DOUBLE_EQ(
1.0, body4->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body4->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body4->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body4->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirection()
.squaredNorm());
EXPECT_EQ(
nullptr,
body4->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirectionFrame());
// this body is rotated by 45 degrees, but set friction direction according to
// world frame so that the body orientation doesn't matter. thus a diagonal
// axis is needed to push it in x and y
body4->getShapeNode(0)->getDynamicsAspect()->setPrimaryFrictionCoeff(0.0);
body4->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirectionFrame(
Frame::World());
body4->getShapeNode(0)->getDynamicsAspect()->setFirstFrictionDirection(
Eigen::Vector3d(0.5 * std::sqrt(2), 0.5 * std::sqrt(2), 0));
// check friction values
EXPECT_DOUBLE_EQ(
0.5, body4->getShapeNode(0)->getDynamicsAspect()->getFrictionCoeff());
EXPECT_DOUBLE_EQ(
0.0,
body4->getShapeNode(0)->getDynamicsAspect()->getPrimaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body4->getShapeNode(0)->getDynamicsAspect()->getSecondaryFrictionCoeff());
EXPECT_DOUBLE_EQ(
1.0,
body4->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirection()
.squaredNorm());
EXPECT_EQ(
Frame::World(),
body4->getShapeNode(0)
->getDynamicsAspect()
->getFirstFrictionDirectionFrame());
// Create a world and add the rigid body
auto world = simulation::World::create();
EXPECT_TRUE(equals(world->getGravity(), ::Eigen::Vector3d(0, 0, -9.81)));
world->setGravity(Eigen::Vector3d(0.0, -5.0, -9.81));
EXPECT_TRUE(equals(world->getGravity(), ::Eigen::Vector3d(0.0, -5.0, -9.81)));
world->addSkeleton(createFloor());
world->addSkeleton(skeleton1);
world->addSkeleton(skeleton2);
world->addSkeleton(skeleton3);
world->addSkeleton(skeleton4);
const auto numSteps = 500;
for (auto i = 0u; i < numSteps; ++i)
{
world->step();
// Wait until the first box settle-in on the ground
if (i > 300)
{
const auto x1 = body1->getTransform().translation()[0];
const auto y1 = body1->getTransform().translation()[1];
EXPECT_NEAR(x1, -0.5, 0.00001);
EXPECT_NEAR(y1, -0.17889, 0.001);
// The second box still moves even after landing on the ground because its
// friction is zero.
const auto x2 = body2->getTransform().translation()[0];
const auto y2 = body2->getTransform().translation()[1];
EXPECT_NEAR(x2, 0.5, 0.00001);
EXPECT_LE(y2, -0.17889);
// The third box still moves even after landing on the ground because its
// friction is zero along the first friction direction.
const auto x3 = body3->getTransform().translation()[0];
const auto y3 = body3->getTransform().translation()[1];
EXPECT_GE(x3, 1.5249);
EXPECT_LE(y3, -0.20382);
// The fourth box still moves even after landing on the ground because its
// friction is zero along the first friction direction.
const auto x4 = body4->getTransform().translation()[0];
const auto y4 = body4->getTransform().translation()[1];
EXPECT_LE(x4, -1.5249);
EXPECT_LE(y4, -0.20382);
}
}
}
|