File size: 10,302 Bytes
2c55b92 | 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 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 | // Copyright 2022 DeepMind Technologies Limited
//
// 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.
// Tests for plugin-related functionalities.
#include <cmath>
#include <limits>
#include <vector>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <mujoco/mujoco.h>
#include "test/fixture.h"
namespace mujoco {
namespace {
using ElasticityTest = PluginTest;
// -------------------------------- flex ------------------------------------
TEST_F(ElasticityTest, FlexCompatibility) {
static constexpr char flex_xml[] = R"(
<mujoco>
<worldbody>
<body name="parent">
<flexcomp name="soft" type="grid" count="3 3 3"
radius="0.01" dim="3"mass="1">
<pin id="2"/>
<elasticity young="5e4" poisson="0.2"/>
</flexcomp>
</body>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(flex_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mjData* d = mj_makeData(m);
mj_deleteData(d);
mj_deleteModel(m);
}
// -------------------------------- shell -----------------------------------
TEST_F(ElasticityTest, ElasticEnergyShell) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<worldbody>
<flexcomp type="grid" count="8 8 1" spacing="1 1 1"
radius=".025" name="test" dim="2">
<elasticity young="2" poisson="0" thickness="1"/>
</flexcomp>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mjData* d = mj_makeData(m);
mj_kinematics(m, d);
mj_flex(m, d);
// check that a plane is in the kernel of the energy
for (mjtNum scale = 1; scale < 4; scale++) {
for (int e = 0; e < m->flex_edgenum[0]; e++) {
int* edge = m->flex_edge + 2*(m->flex_edgeadr[0] + e);
int* flap = m->flex_edgeflap + 2*(m->flex_edgeadr[0] + e);
int v[4] = {edge[0], edge[1], flap[0], flap[1]};
if (v[3]== -1) {
continue;
}
mjtNum energy = 0;
mjtNum volume = 1./2.;
for (int i = 0; i < 4; i++) {
for (int j = 0; j < 4; j++) {
for (int x = 0; x < 3; x++) {
mjtNum elongation1 = scale * d->flexvert_xpos[3*v[i]+x];
mjtNum elongation2 = scale * d->flexvert_xpos[3*v[j]+x];
energy += m->flex_bending[16*e+4*i+j] * elongation1 * elongation2;
}
}
}
EXPECT_NEAR(
4*energy/volume, 0, std::numeric_limits<float>::epsilon());
}
}
mj_deleteData(d);
mj_deleteModel(m);
}
// -------------------------------- membrane -----------------------------------
TEST_F(PluginTest, ElasticEnergyMembrane) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<worldbody>
<flexcomp type="grid" count="8 8 1" spacing="1 1 1"
radius=".025" name="test" dim="2">
<elasticity young="2" poisson="0" thickness="1" elastic2d="stretch"/>
<edge equality="false"/>
</flexcomp>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mjData* d = mj_makeData(m);
mj_kinematics(m, d);
mj_flex(m, d);
mjtNum* metric = m->flex_stiffness + 21 * m->flex_elemadr[0];
// check that if the entire geometry is rescaled by a factor "scale", then
// trace(strain^2) = 2*scale^2
for (mjtNum scale = 1; scale < 4; scale++) {
for (int t = 0; t < m->flex_elemnum[0]; t++) {
mjtNum energy = 0;
mjtNum volume = 1./2.;
int idx = 0;
for (int e1 = 0; e1 < 3; e1++) {
for (int e2 = e1; e2 < 3; e2++) {
int idx1 = m->flex_elemedge[3*t+e1 + m->flex_elemedgeadr[0]];
int idx2 = m->flex_elemedge[3*t+e2 + m->flex_elemedgeadr[0]];
mjtNum elong1 =
scale * m->flexedge_length0[idx1] * m->flexedge_length0[idx1];
mjtNum elong2 =
scale * m->flexedge_length0[idx2] * m->flexedge_length0[idx2];
energy += metric[21*t+idx++] * elong1 * elong2 * (e1 == e2 ? 1. : 2.);
}
}
EXPECT_NEAR(
4*energy/volume, 2*scale*scale, std::numeric_limits<float>::epsilon());
}
}
mj_deleteData(d);
mj_deleteModel(m);
}
// -------------------------------- solid -----------------------------------
TEST_F(ElasticityTest, ElasticEnergySolid) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<worldbody>
<flexcomp type="grid" count="8 8 8" spacing="1 1 1"
radius=".025" name="test" dim="3">
<elasticity young="2" poisson="0"/>
<edge equality="false"/>
</flexcomp>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mjData* d = mj_makeData(m);
mj_kinematics(m, d);
mj_flex(m, d);
mjtNum* metric = m->flex_stiffness + 21 * m->flex_elemadr[0];
// check that if the entire geometry is rescaled by a factor "scale", then
// trace(strain^2) = 3*scale^2
for (mjtNum scale = 1; scale < 4; scale++) {
for (int t = 0; t < m->flex_elemnum[0]; t++) {
mjtNum energy = 0;
mjtNum volume = 1./6.;
int idx = 0;
for (int e1 = 0; e1 < 6; e1++) {
for (int e2 = e1; e2 < 6; e2++) {
int idx1 = m->flex_elemedge[6*t+e1 + m->flex_elemedgeadr[0]];
int idx2 = m->flex_elemedge[6*t+e2 + m->flex_elemedgeadr[0]];
mjtNum elong1 =
scale * m->flexedge_length0[idx1] * m->flexedge_length0[idx1];
mjtNum elong2 =
scale * m->flexedge_length0[idx2] * m->flexedge_length0[idx2];
energy += metric[21*t+idx++] * elong1 * elong2 * (e1 == e2 ? 1. : 2.);
}
}
EXPECT_NEAR(
energy/volume, 3*scale*scale, std::numeric_limits<float>::epsilon());
}
}
mj_deleteData(d);
mj_deleteModel(m);
}
// -------------------------------- cable -----------------------------------
TEST_F(ElasticityTest, CantileverIntoCircle) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<option gravity="0 0 0"/>
<extension>
<plugin plugin="mujoco.elasticity.cable"/>
</extension>
<worldbody>
<geom type="plane" size="0 0 1" quat="1 0 0 0"/>
<site name="reference" pos="0 0 0"/>
<composite type="cable" curve="s" count="41 1 1" size="1" offset="0 0 1" initial="none">
<plugin plugin="mujoco.elasticity.cable">
<config key="twist" value="1e6"/>
<config key="bend" value="1e9"/>
</plugin>
<joint kind="main" damping="2"/>
<geom type="capsule" size=".005" density="1"/>
</composite>
</worldbody>
<contact>
<exclude body1="B_first" body2="B_last"/>
</contact>
<sensor>
<framepos objtype="site" objname="S_last"/>
</sensor>
<actuator>
<motor site="S_last" gear="0 0 0 0 1 0" ctrllimited="true" ctrlrange="0 4"/>
</actuator>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mjData* d = mj_makeData(m);
// see Oliver Weeger, Sai-Kit Yeung, Martin L. Dunn, "Isogeometric collocation methods for Cosserat rods and rod
// structures", section 7.1 (DOI: j.cma.2016.05.009), the torque for achieving an angle phi is phi * E * Iy.
mjtNum Iy = mjPI * pow(0.005, 4) / 4;
mjtNum torque = 2 * mjPI * 1e9 * Iy;
for (int i=0; i < 1300; i++) {
if (i < 300) {
d->ctrl[0] += torque / 300;
}
mj_step(m, d);
}
EXPECT_NEAR(d->sensordata[0], 0, std::numeric_limits<float>::epsilon());
EXPECT_NEAR(d->sensordata[1], 0, std::numeric_limits<float>::epsilon());
EXPECT_NEAR(d->sensordata[2], 1, std::numeric_limits<float>::epsilon());
mj_deleteData(d);
mj_deleteModel(m);
}
TEST_F(ElasticityTest, InvalidTxtAttribute) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<extension>
<plugin plugin="mujoco.elasticity.cable">
<instance name="invalid">
<config key="twist" value="one"/>
<config key="bend" value="1"/>
</instance>
</plugin>
</extension>
<worldbody>
<geom type="plane" size="0 0 1" quat="1 0 0 0"/>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::IsNull());
}
TEST_F(ElasticityTest, InvalidMixedAttribute) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<extension>
<plugin plugin="mujoco.elasticity.cable">
<instance name="invalid">
<config key="twist" value="1"/>
<config key="bend" value="1 is not a number"/>
</instance>
</plugin>
</extension>
<worldbody>
<geom type="plane" size="0 0 1" quat="1 0 0 0"/>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::IsNull());
}
TEST_F(ElasticityTest, ValidAttributes) {
static constexpr char cantilever_xml[] = R"(
<mujoco>
<extension>
<plugin plugin="mujoco.elasticity.cable">
<instance name="invalid">
<config key="twist" value="0.0"/>
<config key="bend" value=" 0 "/>
</instance>
</plugin>
</extension>
<worldbody>
<geom type="plane" size="0 0 1" quat="1 0 0 0"/>
</worldbody>
</mujoco>
)";
char error[1024] = {0};
mjModel* m = LoadModelFromString(cantilever_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mj_deleteModel(m);
}
} // namespace
} // namespace mujoco
|