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 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441
|
// Copyright 2021 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 engine/engine_sensor.c.
#include <array>
#include <cstddef>
#include <cstdio>
#include <string>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <mujoco/mjmodel.h>
#include <mujoco/mjtnum.h>
#include <mujoco/mujoco.h>
#include "src/engine/engine_support.h"
#include "src/engine/engine_util_blas.h"
#include "src/engine/engine_util_spatial.h"
#include "test/fixture.h"
namespace mujoco {
namespace {
const mjtNum tol = 1e-14; // nearness tolerance for floating point numbers
// returns as a vector the measured values from sensor with index `id`
static std::vector<mjtNum> GetSensor(const mjModel* model,
const mjData* data,
int id) {
return std::vector<mjtNum>(
data->sensordata + model->sensor_adr[id],
data->sensordata + model->sensor_adr[id] + model->sensor_dim[id]);
}
using ::testing::Pointwise;
using ::testing::DoubleNear;
using ::testing::StrEq;
using SensorTest = MujocoTest;
// --------------------- test sensor disableflag -----------------------------
// hand-picked positions and orientations for simple expected values
TEST_F(SensorTest, DisableSensors) {
constexpr char xml[] = R"(
<mujoco>
<sensor>
<clock/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
// before calling anything, check that sensors are initialised to 0
EXPECT_EQ(data->sensordata[0], 0.0);
// call mj_step, mj_step1, expect clock to be incremented by timestep
mj_step(model, data);
mj_step1(model, data);
EXPECT_EQ(data->sensordata[0], model->opt.timestep);
// disable sensors, call mj_step, mj_step1, expect clock to not increment
model->opt.disableflags |= mjDSBL_SENSOR;
mj_step(model, data);
mj_step1(model, data);
EXPECT_EQ(data->time, 2*model->opt.timestep);
EXPECT_EQ(data->sensordata[0], model->opt.timestep);
// re-enable sensors, call mj_step, mj_step1, expect clock to match time
model->opt.disableflags = 0;
mj_step(model, data);
mj_step1(model, data);
EXPECT_EQ(data->time, data->sensordata[0]);
mj_deleteData(data);
mj_deleteModel(model);
}
// --------------------- test relative frame sensors --------------------------
using RelativeFrameSensorTest = MujocoTest;
// hand-picked positions and orientations for simple expected values
TEST_F(RelativeFrameSensorTest, ReferencePosMat) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body name="reference" pos="3 -4 0" xyaxes="4 3 0 -3 4 0"/>
<site name="object" pos="4 3 0" xyaxes="3 -4 0 4 3 0"/>
</worldbody>
<sensor>
<framepos objtype="site" objname="object"
reftype="xbody" refname="reference"/>
<framexaxis objtype="site" objname="object"
reftype="xbody" refname="reference"/>
<frameyaxis objtype="site" objname="object"
reftype="xbody" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
mj_forward(model, data);
// compare actual and expected values
std::vector pos = GetSensor(model, data, 0);
EXPECT_THAT(pos, Pointwise(DoubleNear(tol), {5, 5, 0}));
std::vector xaxis = GetSensor(model, data, 1);
EXPECT_THAT(xaxis, Pointwise(DoubleNear(tol), {0, -1, 0}));
std::vector yaxis = GetSensor(model, data, 2);
EXPECT_THAT(yaxis, Pointwise(DoubleNear(tol), {1, 0, 0}));
mj_deleteData(data);
mj_deleteModel(model);
}
// orientations given by quaternion and by orientation matrix are identical
TEST_F(RelativeFrameSensorTest, ReferenceQuatMat) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<site name="reference" euler="10 20 30"/>
<site name="object" euler="20 40 60"/>
</worldbody>
<sensor>
<framexaxis objtype="site" objname="object"
reftype="site" refname="reference"/>
<frameyaxis objtype="site" objname="object"
reftype="site" refname="reference"/>
<framezaxis objtype="site" objname="object"
reftype="site" refname="reference"/>
<framequat objtype="site" objname="object"
reftype="site" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
// call mj_forward and convert orientation matrix to quaternion
mj_forward(model, data);
mjtNum mat[9], converted_quat[4];
mju_transpose(mat, data->sensordata, 3, 3);
mju_mat2Quat(converted_quat, mat);
// compare quaternion sensor and quat derived from orientation matrix
std::vector quat = GetSensor(model, data, 3);
EXPECT_THAT(quat, Pointwise(DoubleNear(tol), converted_quat));
mj_deleteData(data);
mj_deleteModel(model);
}
// compare global frame and initially co-located relative frame on same body
TEST_F(RelativeFrameSensorTest, ReferencePosMatQuat) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body>
<freejoint/>
<site name="reference"/>
<geom name="object" euler="20 40 60" pos="1 2 3" size="1"/>
</body>
</worldbody>
<sensor>
<framepos objtype="geom" objname="object"/>
<framexaxis objtype="geom" objname="object"/>
<frameyaxis objtype="geom" objname="object"/>
<framezaxis objtype="geom" objname="object"/>
<framequat objtype="geom" objname="object"/>
<framepos objtype="geom" objname="object"
reftype="site" refname="reference"/>
<framexaxis objtype="geom" objname="object"
reftype="site" refname="reference"/>
<frameyaxis objtype="geom" objname="object"
reftype="site" refname="reference"/>
<framezaxis objtype="geom" objname="object"
reftype="site" refname="reference"/>
<framequat objtype="geom" objname="object"
reftype="site" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
constexpr int nsensordata = 32;
ASSERT_EQ(model->nsensordata, nsensordata);
mjData* data = mj_makeData(model);
// call mj_forward, save global sensors (colocated with reference frame)
mj_forward(model, data);
std::vector expected_values(data->sensordata, data->sensordata+nsensordata/2);
// set qpos to arbitrary values, call mj_forward
for (int i=0; i < 7; i++) {
data->qpos[i] = i+1;
}
mj_forward(model, data);
// note that in the loop above the quat is unnormalized, but that's ok,
// quaternions are automatically normalized in place:
EXPECT_NEAR(mju_norm(data->qpos+3, 4), 1.0, tol);
// get values from relative sensors after moving the object
std::vector actual_values(data->sensordata+nsensordata/2,
data->sensordata+nsensordata);
// object and reference have moved together, we expect values to not unchange
EXPECT_THAT(actual_values, Pointwise(DoubleNear(tol), expected_values));
mj_deleteData(data);
mj_deleteModel(model);
}
// hand-picked velocities and orientations for simple expected values
TEST_F(RelativeFrameSensorTest, FrameVelLinearFixed) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body xyaxes="1 -1 0 1 1 0">
<joint type="slide" axis="1 0 0"/>
<geom name="reference" size="1"/>
</body>
<body>
<joint type="slide" axis="1 0 0"/>
<geom name="object" size="1"/>
</body>
</worldbody>
<sensor>
<framelinvel objtype="geom" objname="object"
reftype="geom" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
data->qvel[0] = mju_sqrt(2);
data->qvel[1] = 1;
mj_forward(model, data);
// compare to expected values
std::vector linvel = GetSensor(model, data, 0);
const mjtNum expected_linvel[3] = {-mju_sqrt(0.5), mju_sqrt(0.5), 0};
EXPECT_THAT(linvel, Pointwise(DoubleNear(tol), expected_linvel));
mj_deleteData(data);
mj_deleteModel(model);
}
// object and reference in the same body, expect angular velocites to be zero
TEST_F(RelativeFrameSensorTest, FrameVelAngFixed) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body>
<joint type="hinge" axis="1 2 3"/>
<geom name="reference" size="1" pos="1 2 3"/>
<geom name="object" size="1" pos="-3 -2 -1"/>
</body>
</worldbody>
<sensor>
<frameangvel objtype="geom" objname="object"
reftype="geom" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
// set joint velocities and call forward dynamics
data->qvel[0] = 1;
mj_forward(model, data);
// obj and ref rotate together, relative angular velocites should be zero
std::vector angvel = GetSensor(model, data, 0);
EXPECT_THAT(angvel, Pointwise(DoubleNear(tol), {0, 0, 0}));
mj_deleteData(data);
mj_deleteModel(model);
}
// object and reference rotate on the same global axis
TEST_F(RelativeFrameSensorTest, FrameVelAngOpposing) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body xyaxes="0 -1 0 1 0 0">
<joint type="hinge" axis="0 1 0"/>
<geom name="reference" size="1"/>
</body>
<body>
<joint type="hinge" axis="1 0 0"/>
<geom name="object" size="1" pos="-3 -2 -1"/>
</body>
</worldbody>
<sensor>
<frameangvel objtype="geom" objname="object"
reftype="geom" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
// set joint velocities and call forward dynamics
data->qvel[0] = -1;
data->qvel[1] = 1;
mj_forward(model, data);
// obj and ref rotate on same axis, we can just difference the velocities
std::vector angvel = GetSensor(model, data, 0);
const mjtNum expected_angvel[3] = {0, data->qvel[1]-data->qvel[0], 0};
EXPECT_THAT(angvel, Pointwise(DoubleNear(tol), expected_angvel));
mj_deleteData(data);
mj_deleteModel(model);
}
// two arbitrary frames, compare velocity sensors and fin-diffed positions
TEST_F(RelativeFrameSensorTest, FrameVelGeneral) {
constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body pos="1 2 3" euler="10 20 30">
<joint type="hinge" axis="2 3 4"/>
<geom name="reference" size="1" pos="0 1 2"/>
</body>
<body pos="-3 -2 -1" euler="20 40 60">
<joint type="hinge" axis="2 3 4"/>
<geom name="object" size="1" pos="1 2 3"/>
</body>
</worldbody>
<sensor>
<framepos objtype="geom" objname="object"
reftype="geom" refname="reference"/>
<framequat objtype="geom" objname="object"
reftype="geom" refname="reference"/>
<framelinvel objtype="geom" objname="object"
reftype="geom" refname="reference"/>
<frameangvel objtype="geom" objname="object"
reftype="geom" refname="reference"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
mjtNum dt = 1e-6; // timestep used for finite differencing
// set (arbitrary) joint velocities and call forward dynamics
data->qvel[0] = 1;
data->qvel[1] = -1;
mj_forward(model, data);
// save measured linear and angular velocities as vectors
std::vector linvel = GetSensor(model, data, 2);
std::vector angvel = GetSensor(model, data, 3);
// save current position, quaternion as arrays
mjtNum pos0[3], quat0[4];
mju_copy3(pos0, data->sensordata);
mju_copy4(quat0, data->sensordata+3);
// explicit Euler integration with small dt
mju_addToScl(data->qpos, data->qvel, dt, 2);
// call mj_forward again, save new position and quaternion
mj_forward(model, data);
mjtNum pos1[3], quat1[4];
mju_copy3(pos1, data->sensordata);
mju_copy4(quat1, data->sensordata+3);
// compute expected linear velocities using finite differencing
mjtNum linvel_findiff[3];
mju_sub3(linvel_findiff, pos1, pos0);
mju_scl3(linvel_findiff, linvel_findiff, 1/dt);
// compute expected angular velocities using finite differencing
mjtNum dquat[4], angvel_findiff[3];
mju_negQuat(quat0, quat0);
mju_mulQuat(dquat, quat1, quat0);
mju_quat2Vel(angvel_findiff, dquat, dt);
// compare analytic and finite-differenced relative velocities
EXPECT_THAT(linvel, Pointwise(DoubleNear(10*dt), linvel_findiff));
EXPECT_THAT(angvel, Pointwise(DoubleNear(10*dt), angvel_findiff));
mj_deleteData(data);
mj_deleteModel(model);
}
// ------------------------- general sensor tests -----------------------------
using SensorTest = MujocoTest;
// test clock sensor
TEST_F(SensorTest, Clock) {
constexpr char xml[] = R"(
<mujoco>
<option timestep="1e-3"/>
<sensor>
<clock/>
<clock name="clampedclock" cutoff="3e-3"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml, 0, 0);
mjData* data = mj_makeData(model);
// call step 4 times, checking that clock works as expected
for (int i=0; i<5; i++) {
mj_step(model, data);
mj_step1(model, data); // update values of position-based sensors
EXPECT_EQ(data->sensordata[0], data->time);
EXPECT_EQ(data->sensordata[1], mju_min(data->time, 3e-3));
}
// chack names
const char* name0 = mj_id2name(model, mjOBJ_SENSOR, 0);
EXPECT_EQ(name0, nullptr);
const char* name1 = mj_id2name(model, mjOBJ_SENSOR, 1);
EXPECT_THAT(name1, StrEq("clampedclock"));
mj_deleteData(data);
mj_deleteModel(model);
}
} // namespace
} // namespace mujoco
|