Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 9 additions & 6 deletions test/engine/engine_collision_box_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@ static const char* const kBad1FilePath =
TEST_F(MjCollisionBoxTest, BadContacts) {
for (const char* local_path : {kBad0FilePath, kBad1FilePath}) {
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
mj_forward(model, data);

Expand Down Expand Up @@ -141,8 +142,9 @@ static const char* const kDuplicateFilePath =

TEST_F(MjCollisionBoxTest, DuplicateContacts) {
const std::string xml_path = GetTestDataFilePath(kDuplicateFilePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
mj_forward(model, data);

Expand Down Expand Up @@ -232,8 +234,9 @@ static const char* const kDeepFilePath =

TEST_F(MjCollisionBoxTest, DeepPenetration) {
const std::string xml_path = GetTestDataFilePath(kDeepFilePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
mj_forward(model, data);

Expand Down
11 changes: 5 additions & 6 deletions test/engine/engine_collision_convex_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,7 @@ using MjcConvexTest = MujocoTest;
TEST_F(MjcConvexTest, FramelessContact) {
const std::string xml_path = GetTestDataFilePath(kFramelessContactPath);
char error[1024];
const std::size_t error_sz = 1024;
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, error_sz);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
// Loading used to fail with "engine error: xaxis of contact frame undefined".
EXPECT_THAT(model, NotNull()) << "Failed to load model: " << error;
mj_deleteModel(model);
Expand All @@ -50,17 +49,17 @@ TEST_F(MjcConvexTest, FramelessContact) {
TEST_F(MjcConvexTest, FramelessContactHfield) {
const std::string xml_path = GetTestDataFilePath(kFramelessContactHfieldPath);
char error[1024];
const std::size_t error_sz = 1024;
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, error_sz);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
// Loading used to fail with "engine error: xaxis of contact frame undefined".
EXPECT_THAT(model, NotNull()) << "Failed to load model: " << error;
mj_deleteModel(model);
}

TEST_F(MjcConvexTest, CylinderBox) {
const std::string xml_path = GetTestDataFilePath(kCylinderBoxPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

// with multiCCD enabled, should find 5 contacts
Expand Down
8 changes: 6 additions & 2 deletions test/engine/engine_collision_driver_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,9 @@ TEST_F(MjCollisionTest, AllCollisions) {
static const char* const kModelFilePath =
"engine/testdata/collisions.xml";
const std::string xml_path = GetTestDataFilePath(kModelFilePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

// mjCOL_ALL is the default
Expand Down Expand Up @@ -87,7 +89,9 @@ TEST_F(MjCollisionTest, ZeroedHessian) {
static const char* const kModelFilePath =
"engine/testdata/collisions.xml";
const std::string xml_path = GetTestDataFilePath(kModelFilePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

mj_fwdPosition(model, data);
Expand Down
8 changes: 6 additions & 2 deletions test/engine/engine_core_constraint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,9 @@ TEST_F(CoreConstraintTest, JacobianPreAllocate) {

// iterate through dense and sparse
for (mjtJacobian sparsity : {mjJAC_DENSE, mjJAC_SPARSE}) {
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
model->opt.jacobian = sparsity;
mjData* data = mj_makeData(model);

Expand All @@ -261,7 +263,9 @@ TEST_F(CoreConstraintTest, EqualityBodySite) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/equality_site_body_compare.xml");

mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

// simulate, get diag(A)
Expand Down
24 changes: 15 additions & 9 deletions test/engine/engine_core_smooth_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -411,8 +411,9 @@ TEST_F(CoreSmoothTest, TendonInertiaEquivalent) {
// test that bodies hanging on connects lead to expected force sensor readings
void TestConnect(const char* const filepath) {
const std::string xml_path = GetTestDataFilePath(filepath);
mjModel* model =
mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);
// settle physics:
for (int i=0; i < 1000; i++) {
Expand Down Expand Up @@ -466,8 +467,9 @@ TEST_F(CoreSmoothTest, RnePostConnectMultipleConstraints) {
// test that bodies attached with welds lead to expected force sensor readings
void TestWeld(const char* const filepath) {
const std::string xml_path = GetTestDataFilePath(filepath);
mjModel* model =
mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);
// settle physics:
for (int i=0; i < 1000; i++) {
Expand Down Expand Up @@ -553,7 +555,9 @@ TEST_F(CoreSmoothTest, EqualityBodySite) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/equality_site_body_compare.xml");

mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

// simulate, get sensordata
Expand Down Expand Up @@ -589,8 +593,9 @@ TEST_F(CoreSmoothTest, EqualityBodySite) {
TEST_F(CoreSmoothTest, RefsiteBringsToPose) {
constexpr char kRefsitePath[] = "engine/testdata/actuation/refsite.xml";
const std::string xml_path = GetTestDataFilePath(kRefsitePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

// set pose target in ctrl (3 positions, 3 rotations)
Expand Down Expand Up @@ -632,8 +637,9 @@ TEST_F(CoreSmoothTest, RefsiteBringsToPose) {
TEST_F(CoreSmoothTest, RefsiteConservesMomentum) {
constexpr char kRefsitePath[] = "engine/testdata/actuation/refsite_free.xml";
const std::string xml_path = GetTestDataFilePath(kRefsitePath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

data->ctrl[0] = 1;
Expand Down
33 changes: 24 additions & 9 deletions test/engine/engine_derivative_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,9 @@ TEST_F(DerivativeTest, SmoothDvel) {
kDampedActuatorsPath,
kDamperActuatorsPath}) {
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
int nD = model->nD;
mjData* data = mj_makeData(model);

Expand Down Expand Up @@ -290,7 +292,9 @@ TEST_F(DerivativeTest, PassiveDvel) {
kTumblingThinObjectEllipsoidPath}) {
// load model
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
int nD = model->nD;
mjData* data = mj_makeData(model);
// allocate Jacobians
Expand Down Expand Up @@ -335,7 +339,9 @@ TEST_F(DerivativeTest, PassiveDvel) {
// mj_stepSkip computes the same next state as mj_step
TEST_F(DerivativeTest, StepSkip) {
const std::string xml_path = GetTestDataFilePath(kDampedPendulumPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
int nq = model->nq;
int nv = model->nv;
Expand Down Expand Up @@ -478,7 +484,9 @@ static void LinearSystem(const mjModel* m, mjData* d, mjtNum* A, mjtNum* B) {
// compare FD derivatives to analytic derivatives of linear dynamical system
TEST_F(DerivativeTest, LinearSystem) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu;

Expand Down Expand Up @@ -538,7 +546,9 @@ TEST_F(DerivativeTest, LinearSystem) {
// check ctrl derivatives at the range limit
TEST_F(DerivativeTest, ClampedCtrlDerivatives) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu;

Expand Down Expand Up @@ -697,8 +707,9 @@ TEST_F(DerivativeTest, SensorSkip) {
// derivatives don't mutate the state
TEST_F(DerivativeTest, NoStateMutation) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data0 = mj_makeData(model);
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu, na = model->na, ns = model->nsensordata;
Expand Down Expand Up @@ -755,7 +766,9 @@ TEST_F(DerivativeTest, DenseSparseRneEquivalent) {
kDampedActuatorsPath,
kDamperActuatorsPath}) {
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
int nD = model->nD;
mjtNum* qDeriv = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD);
mjData* data = mj_makeData(model);
Expand Down Expand Up @@ -794,7 +807,9 @@ TEST_F(DerivativeTest, DenseSparseRneEquivalent) {
// compare FD inverse derivatives to analytic derivatives of linear system
TEST_F(DerivativeTest, LinearSystemInverse) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

int nv = model->nv;
Expand Down
24 changes: 16 additions & 8 deletions test/engine/engine_forward_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ static const char* const kArmatureEquivalencePath =
// a gear ratio enforced by an equality
TEST_F(ForwardTest, ArmatureEquivalence) {
const std::string xml_path = GetTestDataFilePath(kArmatureEquivalencePath);
char error[1000];
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
Expand Down Expand Up @@ -383,7 +383,9 @@ TEST_F(ImplicitIntegratorTest, EulerImplicitEquivalent) {
// Joint and actuator damping should integrate identically under implicit
TEST_F(ImplicitIntegratorTest, JointActuatorEquivalent) {
const std::string xml_path = GetTestDataFilePath(kDampedActuatorsPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

// take 1000 steps with Euler
Expand Down Expand Up @@ -413,7 +415,9 @@ TEST_F(ImplicitIntegratorTest, JointActuatorEquivalent) {
TEST_F(ImplicitIntegratorTest, EnergyConservation) {
const std::string xml_path =
GetTestDataFilePath(kEnergyConservingPendulumPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

const int nstep = 500; // number of steps to take
Expand Down Expand Up @@ -949,7 +953,9 @@ TEST_F(ActuatorTest, ExpectedAdhesionForce) {
// Actuator force clamping at joints
TEST_F(ActuatorTest, ActuatorForceClamping) {
const std::string xml_path = GetTestDataFilePath(kJointForceClamp);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

data->ctrl[0] = 10;
Expand Down Expand Up @@ -1101,7 +1107,7 @@ TEST_F(ActuatorTest, DampRatio) {
TEST_F(ActuatorTest, DampRatioTendon) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/actuation/tendon_dampratio.xml");
char error[1000];
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);
Expand Down Expand Up @@ -1275,7 +1281,7 @@ using ActEarlyTest = MujocoTest;
TEST_F(ActEarlyTest, RemovesOneStepDelay) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/actuation/actearly.xml");
char error[1000];
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;

Expand Down Expand Up @@ -1326,7 +1332,7 @@ TEST_F(ActEarlyTest, RemovesOneStepDelay) {
TEST_F(ActEarlyTest, DoesntChangeStateInMjForward) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/actuation/actearly.xml");
char error[1000];
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;

Expand Down Expand Up @@ -1426,7 +1432,9 @@ TEST_F(ActuatorTest, DisableActuatorOutOfRange) {

TEST_F(ActuatorTest, TendonActuatorForceRange) {
const std::string xml_path = GetTestDataFilePath(kTendonForceClamp);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

EXPECT_EQ(model->tendon_actfrclimited[0], 0);
Expand Down
5 changes: 3 additions & 2 deletions test/engine/engine_passive_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -186,8 +186,9 @@ using TendonTest = MujocoTest;
TEST_F(TendonTest, SpringrangeDeadband) {
const std::string xml_path =
GetTestDataFilePath("engine/testdata/tendon_springlength.xml");
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
ASSERT_THAT(model, NotNull());
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
mjData* data = mj_makeData(model);

// initial state outside deadband: spring is active
Expand Down
8 changes: 6 additions & 2 deletions test/engine/engine_support_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -693,7 +693,9 @@ static const char* const kDefaultModel = "testdata/model.xml";

TEST_F(SupportTest, GetSetStateStepEqual) {
const std::string xml_path = GetTestDataFilePath(kDefaultModel);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

// make distribution using seed
Expand Down Expand Up @@ -746,7 +748,9 @@ TEST_F(SupportTest, GetSetStateStepEqual) {

TEST_F(SupportTest, ExtractState) {
const std::string xml_path = GetTestDataFilePath(kDefaultModel);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error;
mjData* data = mj_makeData(model);

// make distribution using seed
Expand Down
10 changes: 6 additions & 4 deletions test/engine/engine_vis_visualize_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,9 @@ class MjvSceneTest : public MujocoTest {

TEST_F(MjvSceneTest, UpdateScene) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << kModelPath;
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << error;

InitSceneObjects(model);

Expand Down Expand Up @@ -87,8 +88,9 @@ TEST_F(MjvSceneTest, UpdateScene) {

TEST_F(MjvSceneTest, UpdateSceneGeomsExhausted) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << kModelPath;
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << error;

const int maxgeoms = 1;
InitSceneObjects(model, maxgeoms);
Expand Down