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
8a8a4eca
Commit
8a8a4eca
authored
May 18, 2020
by
Pierre Fernbach
Browse files
[Tests] add more tests cases for the de serialization of examples
parent
d6e897ac
Changes
2
Hide whitespace changes
Inline
Side-by-side
unittest/examples.cpp
View file @
8a8a4eca
...
...
@@ -59,6 +59,8 @@ BOOST_AUTO_TEST_CASE(step_in_place) {
cs
.
loadFromBinary
(
path
+
"step_in_place.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_COM
)
{
...
...
@@ -69,6 +71,9 @@ BOOST_AUTO_TEST_CASE(step_in_place_COM) {
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_REF
)
{
...
...
@@ -81,6 +86,9 @@ BOOST_AUTO_TEST_CASE(step_in_place_REF) {
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
(
1e-6
,
false
));
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_WB
)
{
...
...
@@ -96,6 +104,8 @@ BOOST_AUTO_TEST_CASE(step_in_place_WB) {
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic
)
{
...
...
@@ -103,6 +113,8 @@ BOOST_AUTO_TEST_CASE(step_in_place_quasistatic) {
cs
.
loadFromBinary
(
path
+
"step_in_place_quasistatic.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
9
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_COM
)
{
...
...
@@ -113,6 +125,8 @@ BOOST_AUTO_TEST_CASE(step_in_place_quasistatic_COM) {
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_REF
)
{
...
...
@@ -124,6 +138,8 @@ BOOST_AUTO_TEST_CASE(step_in_place_quasistatic_REF) {
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
step_in_place_quasistatic_WB
)
{
...
...
@@ -139,6 +155,8 @@ BOOST_AUTO_TEST_CASE(step_in_place_quasistatic_WB) {
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm
)
{
...
...
@@ -146,6 +164,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm) {
cs
.
loadFromBinary
(
path
+
"walk_20cm.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_COM
)
{
...
...
@@ -156,6 +176,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_COM) {
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_REF
)
{
...
...
@@ -167,6 +189,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_REF) {
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_WB
)
{
...
...
@@ -182,6 +206,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_WB) {
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic
)
{
...
...
@@ -189,6 +215,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_quasistatic) {
cs
.
loadFromBinary
(
path
+
"walk_20cm_quasistatic.cs"
);
BOOST_CHECK_EQUAL
(
cs
.
size
(),
23
);
BOOST_CHECK
(
cs
.
haveConsistentContacts
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_COM
)
{
...
...
@@ -199,6 +227,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_quasistatic_COM) {
BOOST_CHECK
(
cs
.
haveTimings
());
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
!
cs
.
haveFriction
());
BOOST_CHECK
(
!
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_REF
)
{
...
...
@@ -210,6 +240,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_quasistatic_REF) {
BOOST_CHECK
(
cs
.
haveCentroidalValues
());
BOOST_CHECK
(
cs
.
haveCentroidalTrajectories
());
BOOST_CHECK
(
cs
.
haveEffectorsTrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_CASE
(
walk_20cm_quasistatic_WB
)
{
...
...
@@ -225,6 +257,8 @@ BOOST_AUTO_TEST_CASE(walk_20cm_quasistatic_WB) {
BOOST_CHECK
(
cs
.
haveJointsDerivativesTrajectories
());
BOOST_CHECK
(
cs
.
haveContactForcesTrajectories
());
BOOST_CHECK
(
cs
.
haveZMPtrajectories
());
BOOST_CHECK
(
cs
.
haveFriction
());
BOOST_CHECK
(
cs
.
haveContactModelDefined
());
}
BOOST_AUTO_TEST_SUITE_END
()
unittest/python/serialization_examples.py
View file @
8a8a4eca
...
...
@@ -129,6 +129,8 @@ class ExamplesSerialization(unittest.TestCase):
cs
.
loadFromBinary
(
str
(
PATH
/
"step_in_place.cs"
))
self
.
assertEqual
(
cs
.
size
(),
9
)
self
.
assertTrue
(
cs
.
haveConsistentContacts
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
def
test_step_in_place_COM
(
self
):
cs
=
ContactSequence
()
...
...
@@ -138,6 +140,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveTimings
())
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
effector
=
False
,
wholeBody
=
False
)
def
test_step_in_place_REF
(
self
):
...
...
@@ -150,6 +154,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertTrue
(
cs
.
haveEffectorsTrajectories
())
self
.
assertTrue
(
cs
.
haveEffectorsTrajectories
(
1e-6
,
False
))
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
root
=
True
,
effector
=
True
,
wholeBody
=
False
)
def
test_step_in_place_WB
(
self
):
...
...
@@ -165,6 +171,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveJointsDerivativesTrajectories
())
self
.
assertTrue
(
cs
.
haveContactForcesTrajectories
())
self
.
assertTrue
(
cs
.
haveZMPtrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
effector
=
True
,
wholeBody
=
True
)
def
test_step_in_place_quasistatic
(
self
):
...
...
@@ -172,6 +180,8 @@ class ExamplesSerialization(unittest.TestCase):
cs
.
loadFromBinary
(
str
(
PATH
/
"step_in_place_quasistatic.cs"
))
self
.
assertEqual
(
cs
.
size
(),
9
)
self
.
assertTrue
(
cs
.
haveConsistentContacts
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
def
test_step_in_place_quasistatic_COM
(
self
):
cs
=
ContactSequence
()
...
...
@@ -181,6 +191,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveTimings
())
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
quasistatic
=
True
,
effector
=
False
,
wholeBody
=
False
)
def
test_step_in_place_quasistatic_REF
(
self
):
...
...
@@ -192,6 +204,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertTrue
(
cs
.
haveEffectorsTrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
root
=
True
,
quasistatic
=
True
,
effector
=
True
,
wholeBody
=
False
)
def
test_step_in_place_quasistatic_WB
(
self
):
...
...
@@ -207,12 +221,16 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveJointsDerivativesTrajectories
())
self
.
assertTrue
(
cs
.
haveContactForcesTrajectories
())
self
.
assertTrue
(
cs
.
haveZMPtrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
quasistatic
=
True
,
effector
=
True
,
wholeBody
=
True
)
def
test_walk_20cm
(
self
):
cs
=
ContactSequence
()
cs
.
loadFromBinary
(
str
(
PATH
/
"walk_20cm.cs"
))
self
.
assertEqual
(
cs
.
size
(),
23
)
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
self
.
assertTrue
(
cs
.
haveConsistentContacts
())
def
test_walk_20cm_COM
(
self
):
...
...
@@ -223,6 +241,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveTimings
())
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
effector
=
False
,
wholeBody
=
False
)
def
test_walk_20cm_REF
(
self
):
...
...
@@ -234,6 +254,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertTrue
(
cs
.
haveEffectorsTrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
root
=
True
,
effector
=
True
,
wholeBody
=
False
)
def
test_walk_20cm_WB
(
self
):
...
...
@@ -249,12 +271,16 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveJointsDerivativesTrajectories
())
self
.
assertTrue
(
cs
.
haveContactForcesTrajectories
())
self
.
assertTrue
(
cs
.
haveZMPtrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
effector
=
True
,
wholeBody
=
True
)
def
test_walk_20cm_quasistatic
(
self
):
cs
=
ContactSequence
()
cs
.
loadFromBinary
(
str
(
PATH
/
"walk_20cm_quasistatic.cs"
))
self
.
assertEqual
(
cs
.
size
(),
23
)
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
self
.
assertTrue
(
cs
.
haveConsistentContacts
())
def
test_walk_20cm_quasistatic_COM
(
self
):
...
...
@@ -265,6 +291,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveTimings
())
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertFalse
(
cs
.
haveFriction
())
self
.
assertFalse
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
quasistatic
=
True
,
effector
=
False
,
wholeBody
=
False
)
def
test_walk_20cm_quasistatic_REF
(
self
):
...
...
@@ -276,6 +304,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveCentroidalValues
())
self
.
assertTrue
(
cs
.
haveCentroidalTrajectories
())
self
.
assertTrue
(
cs
.
haveEffectorsTrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
root
=
True
,
quasistatic
=
True
,
effector
=
True
,
wholeBody
=
False
)
def
test_walk_20cm_quasistatic_WB
(
self
):
...
...
@@ -291,6 +321,8 @@ class ExamplesSerialization(unittest.TestCase):
self
.
assertTrue
(
cs
.
haveJointsDerivativesTrajectories
())
self
.
assertTrue
(
cs
.
haveContactForcesTrajectories
())
self
.
assertTrue
(
cs
.
haveZMPtrajectories
())
self
.
assertTrue
(
cs
.
haveFriction
())
self
.
assertTrue
(
cs
.
haveContactModelDefined
())
checkCS
(
self
,
cs
,
quasistatic
=
True
,
effector
=
True
,
wholeBody
=
True
)
...
...
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