Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
loco-3d
Multicontact-api
Commits
4ddf64ce
Commit
4ddf64ce
authored
Feb 11, 2020
by
Pierre Fernbach
Browse files
[Tests] add unit test for deserialization of the objects in examples/
parent
225bbeb1
Changes
2
Hide whitespace changes
Inline
Side-by-side
unittest/CMakeLists.txt
View file @
4ddf64ce
...
...
@@ -6,6 +6,7 @@ ADD_DEFINITIONS(-DBOOST_TEST_DYN_LINK)
SET
(
${
PROJECT_NAME
}
_TESTS
geometry
scenario
examples
)
FOREACH
(
TEST
${${
PROJECT_NAME
}
_TESTS
}
)
...
...
unittest/examples.cpp
0 → 100644
View file @
4ddf64ce
// Copyright (c) 2015-2018, CNRS
// Authors: Justin Carpentier <jcarpent@laas.fr>
#include
<iostream>
#define BOOST_TEST_MODULE StatsTests
#include
<boost/test/unit_test.hpp>
#include
<boost/utility/binary.hpp>
#include
"multicontact-api/scenario/contact-sequence.hpp"
#include
"multicontact-api/scenario/fwd.hpp"
#include
"curves/fwd.h"
#include
<curves/so3_linear.h>
#include
<curves/se3_curve.h>
#include
<curves/polynomial.h>
#include
<curves/bezier_curve.h>
#include
<curves/piecewise_curve.h>
#include
<curves/exact_cubic.h>
#include
<curves/cubic_hermite_spline.h>
/**
* This unit test try to deserialize the ContactSequences in the examples folder
* and check if they have the given data set.
* If this test fail, it probably mean that an update of multicontact-api broke the backward compatibility with serialized objects
* The objects need to be re-generated.
*/
using
namespace
multicontact_api
::
scenario
;
const
std
::
string
path
=
"../examples/"
;
BOOST_AUTO_TEST_SUITE
(
BOOST_TEST_MODULE
)
BOOST_AUTO_TEST_CASE
(
com_motion_above_feet_COM
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"com_motion_above_feet_COM.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
1
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
com_motion_above_feet_WB
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"com_motion_above_feet_WB.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
1
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_COM
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_COM.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_REF
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_REF.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_WB
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_WB.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
(
1e-2
));
BOOST_CHECK
(
cs
.
haveJointsTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_quasistatic.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_COM
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_quasistatic_COM.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_REF
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_quasistatic_REF.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_WB
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"step_in_place_quasistatic_WB.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
(
1e-2
));
BOOST_CHECK
(
cs
.
haveJointsTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_COM
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_COM.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_REF
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_REF.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_WB
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_WB.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
(
1e-2
));
BOOST_CHECK
(
cs
.
haveJointsTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_quasistatic.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_COM
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_quasistatic_COM.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_REF
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_quasistatic_REF.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_WB
)
{
ContactSequence
cs
;
cs
.
loadFromBinary
(
path
+
"walk_20cm_quasistatic_WB.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
(
1e-2
));
BOOST_CHECK
(
cs
.
haveJointsTrajectories
());
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
}
BOOST_AUTO_TEST_SUITE_END
()
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment