File size: 22,924 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 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 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 | // 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.
// TODO(b/247110452) add more comments to this file, or add sample plugins
#include "src/engine/engine_plugin.h"
#include <array>
#include <cstdint>
#include <sstream>
#include <string>
#include <string_view>
#include <vector>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <absl/strings/str_format.h>
#include <absl/strings/str_replace.h>
#include <mujoco/mujoco.h>
#include "test/fixture.h"
namespace mujoco {
namespace {
using ::testing::DoubleNear;
using ::testing::HasSubstr;
using ::testing::NotNull;
constexpr int kNumTruePlugins = 9;
constexpr int kNumFakePlugins = 30;
constexpr int kNumTestPlugins = 4;
class BaseTestPlugin {
public:
static constexpr int kDefaultStride = 1;
BaseTestPlugin(const mjModel* m, mjData* d, int instance)
: reset_count(d->plugin_state[m->plugin_stateadr[instance]]),
compute_count(d->plugin_state[m->plugin_stateadr[instance] + 1]),
advance_count(d->plugin_state[m->plugin_stateadr[instance] + 2]) {
{
const char* s = mj_getPluginConfig(m, instance, "stride");
if (*s) {
std::stringstream(s) >> stride;
} else {
stride = kDefaultStride;
}
}
reset_count = 0;
compute_count = 0;
advance_count = 0;
}
void Reset() {
reset_count += stride;
compute_count = 0;
advance_count = 0;
}
void Compute() {
compute_count += stride;
}
void Advance() {
advance_count += stride;
}
protected:
int stride;
mjtNum& reset_count;
mjtNum& compute_count;
mjtNum& advance_count;
};
class TestSensor : public BaseTestPlugin {
public:
TestSensor(const mjModel* m, mjData* d, int instance)
: BaseTestPlugin(m, d, instance) {
for (int i = 0; i < m->nsensor; ++i) {
if (m->sensor_type[i] == mjSENS_PLUGIN &&
m->sensor_plugin[i] == instance) {
sensors.push_back(
reinterpret_cast<mjtNum(*)[4]>(&d->sensordata[m->sensor_adr[i]]));
}
}
}
static int& InitCount() {
static int counter = 0;
return counter;
}
static int& DestroyCount() {
static int counter = 0;
return counter;
}
void Reset() {
BaseTestPlugin::Reset();
WriteSensorData();
}
void Compute() {
BaseTestPlugin::Compute();
WriteSensorData();
}
void Advance() {
BaseTestPlugin::Advance();
WriteSensorData();
}
private:
std::vector<mjtNum (*)[4]> sensors;
void WriteSensorData() {
for (auto* sensordata_ptr : sensors) {
auto& sensordata = *sensordata_ptr;
sensordata[0] = reset_count;
sensordata[1] = compute_count;
sensordata[2] = advance_count;
}
}
};
class TestActuator : public BaseTestPlugin {
public:
static constexpr mjtNum kDefaultMultiplier = 1.0;
static constexpr mjtNum kActDotValue = 13.0;
TestActuator(const mjModel* m, mjData* d, int instance)
: BaseTestPlugin(m, d, instance), instance_(instance) {
const char* s = mj_getPluginConfig(m, instance, "multiplier");
if (*s) {
std::stringstream(s) >> multiplier;
} else {
multiplier = kDefaultMultiplier;
}
for (int i = 0; i < m->nu; ++i) {
if (m->actuator_plugin[i] == instance) {
actuators.push_back(&d->actuator_force[i]);
}
}
}
static int& InitCount() {
static int counter = 0;
return counter;
}
static int& DestroyCount() {
static int counter = 0;
return counter;
}
void Reset() {
BaseTestPlugin::Reset();
WriteActuatorForce();
}
void Compute() {
BaseTestPlugin::Compute();
WriteActuatorForce();
}
void ActDot(const mjModel* m, mjData* d) {
for (int i = 0; i < m->nu; ++i) {
if (m->actuator_plugin[i] != instance_) {
continue;
}
// If the user specified an actdim, fill the act_dot values that belong
// to the plugin.
int actnum = m->actuator_actnum[i];
if (m->actuator_dyntype[i] != mjDYN_NONE) {
actnum--;
}
mju_fill(d->act_dot + m->actuator_actadr[i], kActDotValue, actnum);
}
}
private:
mjtNum multiplier;
std::vector<mjtNum*> actuators;
int instance_;
void WriteActuatorForce() {
for (mjtNum* actuator_force : actuators) {
*actuator_force = advance_count * multiplier;
}
}
};
class TestPassive {
public:
TestPassive(const mjModel* m, mjData* d, int instance) {}
void Reset() {}
void Compute() {}
void Advance() {}
};
int RegisterSensorPlugin() {
mjpPlugin plugin;
mjp_defaultPlugin(&plugin);
plugin.name = "mujoco.test.sensor";
const char* attributes[] = {"stride"};
plugin.nattribute = sizeof(attributes) / sizeof(*attributes);
plugin.attributes = attributes;
plugin.capabilityflags |= mjPLUGIN_SENSOR;
plugin.nstate = +[](const mjModel* m, int instance) { return 3; };
plugin.nsensordata =
+[](const mjModel* m, int instance, int sensor_id) { return 3; };
plugin.init = +[](const mjModel* m, mjData* d, int instance) {
auto* sensor = new TestSensor(m, d, instance);
d->plugin_data[instance] = reinterpret_cast<uintptr_t>(sensor);
TestSensor::InitCount()++;
return 0;
};
plugin.destroy = +[](mjData* d, int instance) {
delete reinterpret_cast<TestSensor*>(d->plugin_data[instance]);
d->plugin_data[instance] = 0;
TestSensor::DestroyCount()++;
};
plugin.reset = +[](const mjModel* m, mjtNum* plugin_state, void* plugin_data,
int instance) {
auto sensor = reinterpret_cast<TestSensor*>(plugin_data);
sensor->Reset();
};
plugin.compute = +[](const mjModel* m, mjData* d, int instance, int type) {
auto sensor = reinterpret_cast<TestSensor*>(d->plugin_data[instance]);
sensor->Compute();
};
plugin.advance = +[](const mjModel* m, mjData* d, int instance) {
auto sensor = reinterpret_cast<TestSensor*>(d->plugin_data[instance]);
sensor->Advance();
};
return mjp_registerPlugin(&plugin);
}
int RegisterActuatorPlugin() {
mjpPlugin plugin;
mjp_defaultPlugin(&plugin);
plugin.name = "mujoco.test.actuator";
const char* attributes[] = {"stride", "multiplier"};
plugin.nattribute = sizeof(attributes) / sizeof(*attributes);
plugin.attributes = attributes;
plugin.capabilityflags |= mjPLUGIN_ACTUATOR;
plugin.nstate = +[](const mjModel* m, int instance) { return 3; };
plugin.init = +[](const mjModel* m, mjData* d, int instance) {
auto* actuator = new TestActuator(m, d, instance);
d->plugin_data[instance] = reinterpret_cast<uintptr_t>(actuator);
TestActuator::InitCount()++;
return 0;
};
plugin.destroy = +[](mjData* d, int instance) {
delete reinterpret_cast<TestActuator*>(d->plugin_data[instance]);
d->plugin_data[instance] = 0;
TestActuator::DestroyCount()++;
};
plugin.reset = +[](const mjModel* m, mjtNum* plugin_state, void* plugin_data,
int instance) {
auto actuator = reinterpret_cast<TestActuator*>(plugin_data);
actuator->Reset();
};
plugin.compute = +[](const mjModel* m, mjData* d, int instance, int type) {
auto actuator = reinterpret_cast<TestActuator*>(d->plugin_data[instance]);
actuator->Compute();
};
plugin.advance = +[](const mjModel* m, mjData* d, int instance) {
auto actuator = reinterpret_cast<TestActuator*>(d->plugin_data[instance]);
actuator->Advance();
};
plugin.actuator_act_dot = +[](const mjModel* m, mjData* d, int instance) {
auto actuator = reinterpret_cast<TestActuator*>(d->plugin_data[instance]);
actuator->ActDot(m, d);
};
return mjp_registerPlugin(&plugin);
}
int RegisterPassivePlugin() {
mjpPlugin plugin;
mjp_defaultPlugin(&plugin);
plugin.name = "mujoco.test.passive";
const char* attributes[] = {"attribute"};
plugin.nattribute = sizeof(attributes) / sizeof(*attributes);
plugin.attributes = attributes;
plugin.capabilityflags |= mjPLUGIN_PASSIVE;
plugin.nstate = +[](const mjModel* m, int instance) { return 0; };
plugin.init = +[](const mjModel* m, mjData* d, int instance) {
auto* passive = new TestPassive(m, d, instance);
d->plugin_data[instance] = reinterpret_cast<uintptr_t>(passive);
return 0;
};
plugin.destroy = +[](mjData* d, int instance) {
delete reinterpret_cast<TestPassive*>(d->plugin_data[instance]);
d->plugin_data[instance] = 0;
};
plugin.reset = +[](const mjModel* m, mjtNum* plugin_state, void* plugin_data,
int instance) {
auto passive = reinterpret_cast<TestPassive*>(plugin_data);
passive->Reset();
};
plugin.compute = +[](const mjModel* m, mjData* d, int instance, int type) {
auto passive = reinterpret_cast<TestPassive*>(d->plugin_data[instance]);
passive->Compute();
};
return mjp_registerPlugin(&plugin);
}
int RegisterNoAttributePlugin() {
mjpPlugin plugin;
mjp_defaultPlugin(&plugin);
plugin.name = "mujoco.test.noattribute";
plugin.nattribute = 0;
plugin.attributes = nullptr;
plugin.capabilityflags |= mjPLUGIN_PASSIVE;
plugin.nstate = +[](const mjModel* m, int instance) { return 0; };
plugin.init = +[](const mjModel* m, mjData* d, int instance) {
auto* passive = new TestPassive(m, d, instance);
d->plugin_data[instance] = reinterpret_cast<uintptr_t>(passive);
return 0;
};
plugin.destroy = +[](mjData* d, int instance) {
delete reinterpret_cast<TestPassive*>(d->plugin_data[instance]);
d->plugin_data[instance] = 0;
};
plugin.reset = +[](const mjModel* m, mjtNum* plugin_state, void* plugin_data,
int instance) {
auto passive = reinterpret_cast<TestPassive*>(plugin_data);
passive->Reset();
};
plugin.compute = +[](const mjModel* m, mjData* d, int instance, int type) {
auto passive = reinterpret_cast<TestPassive*>(d->plugin_data[instance]);
passive->Compute();
};
return mjp_registerPlugin(&plugin);
}
class EnginePluginTest : public PluginTest {
public:
// register all plugins
EnginePluginTest() : PluginTest() {
RegisterSensorPlugin();
for (int i = 1; i <= kNumFakePlugins; ++i) {
mjpPlugin plugin;
mjp_defaultPlugin(&plugin);
std::string name = absl::StrFormat("mujoco.test.fake%u", i);
plugin.name = name.c_str();
mjp_registerPlugin(&plugin);
}
RegisterActuatorPlugin();
RegisterPassivePlugin();
RegisterNoAttributePlugin();
}
};
constexpr char xml[] = R"(
<mujoco>
<extension>
<plugin plugin="mujoco.test.sensor">
<instance name="twosensors"/>
<instance name="threesensors">
<config key="stride" value="3"/>
</instance>
</plugin>
<plugin plugin="mujoco.test.actuator">
<instance name="actuator2">
<config key="stride" value="2"/>
<config key="multiplier" value="0.125"/>
</instance>
</plugin>
<plugin plugin="mujoco.test.noattribute">
<instance name="noattribute"/>
</plugin>
<plugin plugin="mujoco.test.passive"/>
</extension>
<worldbody>
<body>
<plugin plugin="mujoco.test.passive">
<config key="attribute" value="0"/>
</plugin>
<geom type="capsule" size="0.1" fromto="-1 0 0 -1 0 -1"/>
<joint name="h1" type="hinge"/>
</body>
<body>
<geom type="capsule" size="0.1" fromto="1 0 0 1 0 -1"/>
<joint name="h2" type="hinge"/>
</body>
</worldbody>
<sensor>
<plugin instance="twosensors"/>
<plugin plugin="mujoco.test.sensor">
<config key="stride" value="5"/>
</plugin>
<plugin instance="threesensors"/>
<plugin instance="twosensors"/>
<plugin instance="threesensors"/>
<plugin instance="threesensors"/>
</sensor>
<actuator>
<plugin joint="h1" plugin="mujoco.test.actuator">
<config key="stride" value="4"/>
<config key="multiplier" value="0.03125"/>
</plugin>
<plugin joint="h2" actdim="3" instance="actuator2"/>
<plugin joint="h2" actdim="4" dyntype="filter" dynprm="0.9" instance="actuator2"/>
</actuator>
</mujoco>
)";
TEST_F(MujocoTest, EmptyPluginDisallowed) {
static constexpr char xml[] = R"(
<mujoco>
<worldbody>
<plugin/>
</worldbody>
</mujoco>
)";
std::array<char, 1024> error;
mjModel* m = LoadModelFromString(xml, error.data(), error.size());
EXPECT_THAT(m, testing::IsNull()) << error.data();
EXPECT_THAT(error.data(), HasSubstr(
"neither 'plugin' nor 'instance' is specified for body 'world'"));
mj_deleteModel(m);
}
TEST_F(PluginTest, FirstPartyPlugins) {
EXPECT_THAT(mjp_pluginCount(), kNumTruePlugins);
}
TEST_F(EnginePluginTest, NoAttributePlugin) {
static constexpr char xml[] = R"(
<mujoco>
<extension>
<plugin plugin="mujoco.test.noattribute">
<instance name="noattribute"/>
</plugin>
</extension>
</mujoco>
)";
std::array<char, 1024> error;
mjModel* m = LoadModelFromString(xml, error.data(), error.size());
EXPECT_THAT(m, testing::NotNull()) << error.data();
mj_deleteModel(m);
}
TEST_F(EnginePluginTest, MultiplePluginTableBlocks) {
EXPECT_EQ(mjp_pluginCount(), kNumTruePlugins + kNumFakePlugins + kNumTestPlugins);
const mjpPlugin* last_plugin = nullptr;
int table_count = 0;
for (int i = 1; i <= kNumFakePlugins; ++i) {
int slot;
std::string name = absl::StrFormat("mujoco.test.fake%u", i);
const mjpPlugin* plugin = mjp_getPlugin(name.c_str(), &slot);
EXPECT_EQ(slot, kNumTruePlugins+i);
EXPECT_THAT(plugin, NotNull());
if (plugin - last_plugin != 1) {
++table_count;
}
last_plugin = plugin;
}
// Make sure that there are enough fake plugins to fill multiple table blocks.
EXPECT_GT(table_count, 1);
// Make sure that a block contains multiple plugins.
EXPECT_LT(table_count, kNumFakePlugins);
}
TEST_F(EnginePluginTest, RegisterIdenticalPlugin) {
EXPECT_EQ(RegisterSensorPlugin(), kNumTruePlugins);
EXPECT_EQ(RegisterActuatorPlugin(), kNumTruePlugins + kNumFakePlugins + 1);
EXPECT_EQ(RegisterPassivePlugin(), kNumTruePlugins + kNumFakePlugins + 2);
EXPECT_EQ(mjp_pluginCount(), kNumTruePlugins + kNumFakePlugins + kNumTestPlugins);
}
TEST_F(EnginePluginTest, SaveXml) {
char error[1024] = {0};
mjModel* m = LoadModelFromString(xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
std::string saved_xml = SaveAndReadXml(m);
std::string_view expected_xml(xml);
const std::string extension_open = "<extension>";
const std::string extension_close = "</extension>";
int extension_start = expected_xml.find(extension_open);
ASSERT_NE(extension_start, std::string::npos);
int extension_end =
expected_xml.find(extension_close) + extension_close.size();
ASSERT_NE(extension_end, std::string::npos);
ASSERT_LE(extension_start, extension_end);
auto expected_extension_section =
expected_xml.substr(extension_start, extension_end - extension_start);
const std::string sensor_open = "<sensor>";
const std::string sensor_close = "</sensor>";
int sensor_start = expected_xml.find(sensor_open);
ASSERT_NE(sensor_start, std::string::npos);
int sensor_end = expected_xml.find(sensor_close) + sensor_close.size();
ASSERT_NE(sensor_end, std::string::npos);
ASSERT_LE(sensor_start, sensor_end);
auto expected_sensor_section =
expected_xml.substr(sensor_start, sensor_end - sensor_start);
const std::string actuator_open = "<actuator>";
const std::string actuator_close = "</actuator>";
int actuator_start = expected_xml.find(actuator_open);
ASSERT_NE(actuator_start, std::string::npos);
int actuator_end = expected_xml.find(actuator_close) + actuator_close.size();
ASSERT_NE(actuator_end, std::string::npos);
ASSERT_LE(actuator_start, actuator_end);
auto expected_actuator_section = absl::StrReplaceAll(
expected_xml.substr(actuator_start, actuator_end - actuator_start),
{{"dynprm=\"0.9\"", "dynprm=\"0.9 0 0 0 0 0 0 0 0 0\""}});
EXPECT_THAT(saved_xml, HasSubstr(expected_extension_section));
EXPECT_THAT(saved_xml, HasSubstr(expected_sensor_section));
EXPECT_THAT(saved_xml, HasSubstr(expected_actuator_section));
mj_deleteModel(m);
// make sure that the saved XML can still be compiled
mjModel* m2 = LoadModelFromString(saved_xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
mj_deleteModel(m2);
}
TEST_F(EnginePluginTest, SensorPlugin) {
int expected_init_count = TestSensor::InitCount();
int expected_destroy_count = TestSensor::DestroyCount();
EXPECT_EQ(expected_init_count, expected_destroy_count);
char error[1024] = {0};
mjModel* m = LoadModelFromString(xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
// mj_makeModel calls mj_makeData and mj_deleteData internally
expected_init_count += 3;
expected_destroy_count += 3;
EXPECT_EQ(TestSensor::InitCount(), expected_init_count);
EXPECT_EQ(TestSensor::DestroyCount(), expected_destroy_count);
EXPECT_EQ(m->nplugin, 7);
EXPECT_EQ(mj_name2id(m, mjOBJ_PLUGIN, "twosensors"), 0);
EXPECT_EQ(mj_name2id(m, mjOBJ_PLUGIN, "threesensors"), 1);
mjData* d = mj_makeData(m);
expected_init_count += 3;
EXPECT_EQ(TestSensor::InitCount(), expected_init_count);
EXPECT_EQ(TestSensor::DestroyCount(), expected_destroy_count);
for (int i = 0; i < 5; ++i) {
for (int j = 0; j < 10; ++j) {
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[3]>(d->plugin_state +
m->plugin_stateadr[0]),
testing::ElementsAreArray<int>({i+1, 2*j, j}));
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[3]>(d->plugin_state +
m->plugin_stateadr[1]),
testing::ElementsAreArray<int>({3*(i+1), 6*j, 3*j}));
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[3]>(d->plugin_state +
m->plugin_stateadr[5]),
testing::ElementsAreArray<int>({5*(i+1), 10*j, 5*j}));
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[18]>(d->sensordata),
testing::ElementsAreArray<int>({ i+1, 2*j, j,
5*(i+1), 10*j, 5*j,
3*(i+1), 6*j, 3*j,
i+1, 2*j, j,
3*(i+1), 6*j, 3*j,
3*(i+1), 6*j, 3*j}));
mj_step(m, d);
mj_forward(m, d);
}
mj_resetData(m, d);
}
mj_deleteData(d);
expected_destroy_count += 3;
EXPECT_EQ(TestSensor::InitCount(), expected_init_count);
EXPECT_EQ(TestSensor::DestroyCount(), expected_destroy_count);
mj_deleteModel(m);
EXPECT_EQ(TestSensor::InitCount(), expected_init_count);
EXPECT_EQ(TestSensor::DestroyCount(), expected_destroy_count);
}
TEST_F(EnginePluginTest, ActuatorPlugin) {
int expected_init_count = TestActuator::InitCount();
int expected_destroy_count = TestActuator::DestroyCount();
EXPECT_EQ(expected_init_count, expected_destroy_count);
char error[1024] = {0};
mjModel* m = LoadModelFromString(xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
// mj_makeModel calls mj_makeData and mj_deleteData internally
expected_init_count += 2;
expected_destroy_count += 2;
EXPECT_EQ(TestActuator::InitCount(), expected_init_count);
EXPECT_EQ(TestActuator::DestroyCount(), expected_destroy_count);
EXPECT_EQ(m->nplugin, 7);
EXPECT_EQ(mj_name2id(m, mjOBJ_PLUGIN, "actuator2"), 2);
mjData* d = mj_makeData(m);
expected_init_count += 2;
EXPECT_EQ(TestActuator::InitCount(), expected_init_count);
EXPECT_EQ(TestActuator::DestroyCount(), expected_destroy_count);
for (int i = 0; i < 5; ++i) {
for (int j = 0; j < 10; ++j) {
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[3]>(d->plugin_state +
m->plugin_stateadr[2]),
testing::ElementsAreArray<int>({2*(i+1), 4*j, 2*j}));
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[3]>(d->plugin_state +
m->plugin_stateadr[3]),
testing::ElementsAreArray<int>({4*(i+1), 8*j, 4*j}));
EXPECT_THAT(*reinterpret_cast<mjtNum(*)[2]>(d->actuator_force),
testing::ElementsAreArray<mjtNum>({0.125*j, 0.25*j}));
mj_step(m, d);
mj_forward(m, d);
}
mj_resetData(m, d);
}
mj_deleteData(d);
expected_destroy_count += 2;
EXPECT_EQ(TestActuator::InitCount(), expected_init_count);
EXPECT_EQ(TestActuator::DestroyCount(), expected_destroy_count);
mj_deleteModel(m);
EXPECT_EQ(TestActuator::InitCount(), expected_init_count);
EXPECT_EQ(TestActuator::DestroyCount(), expected_destroy_count);
}
TEST_F(EnginePluginTest, FilteredActuatorPlugin) {
char error[1024] = {0};
mjModel* m = LoadModelFromString(xml, error, sizeof(error));
ASSERT_THAT(m, testing::NotNull()) << error;
// Expecting 7 actuator state variables: 3x2 from actuator2 instances, and 1
// from setting dyntype="filter" on one of the plugin actuators
ASSERT_EQ(m->na, 7);
EXPECT_EQ(m->actuator_actnum[0], 0);
EXPECT_EQ(m->actuator_actnum[1], 3);
EXPECT_EQ(m->actuator_actnum[2], 4);
EXPECT_EQ(m->actuator_actadr[0], -1);
EXPECT_EQ(m->actuator_actadr[1], 0);
EXPECT_EQ(m->actuator_actadr[2], 3);
mjData* d = mj_makeData(m);
EXPECT_EQ(d->act[0], 0.0);
mju_fill(d->ctrl, 1, m->nu);
// start with nonzero act for the filter
d->act[6] = 0.5;
mj_step(m, d);
for (int i = 0; i < 6; ++i) {
// act_dot should be computed by the plugin
mjtNum expected_act_dot = TestActuator::kActDotValue;
EXPECT_THAT(d->act_dot[i], DoubleNear(expected_act_dot, 1e-6));
// act_dot from the plugin should be Euler-integrated
mjtNum expected_act = expected_act_dot * m->opt.timestep;
EXPECT_THAT(d->act[i], DoubleNear(expected_act, 1e-6));
}
// actuator filter state should be updated outside the plugin for filter
// actuators.
mjtNum expected_act_dot = 0.5 / m->actuator_dynprm[mjNDYN * 2];
EXPECT_THAT(d->act_dot[6], DoubleNear(expected_act_dot, 1e-6));
EXPECT_THAT(d->act[6],
DoubleNear(0.5 + expected_act_dot * m->opt.timestep, 1e-6));
mj_deleteData(d);
mj_deleteModel(m);
}
} // namespace
} // namespace mujoco
|