Skip to content
GitLab
Menu
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
9663d4c4
Commit
9663d4c4
authored
Jan 31, 2020
by
Pierre Fernbach
Browse files
[C++][Python] add CS::haveRootTrajectories
parent
b500b8f8
Changes
2
Show whitespace changes
Inline
Side-by-side
include/multicontact-api/bindings/python/scenario/contact-sequence.hpp
View file @
9663d4c4
...
...
@@ -146,6 +146,9 @@ struct ContactSequencePythonVisitor : public bp::def_visitor<ContactSequencePyth
"Check that a contact force trajectory exist for each active contact.
\n
"
"Also check that the time interval of this trajectories matches the one of the phase.
\n
"
"and that the trajectories start and end and the correct values defined in each phase."
)
.
def
(
"haveRootTrajectories"
,
&
CS
::
haveRootTrajectories
,
"check that a root trajectory exist for each contact phases.
\n
"
"Also check that it start and end at the correct time interval."
)
.
def
(
"getAllEffectorsInContact"
,
&
getAllEffectorsInContactAsList
,
"return a list of names of all the effectors used to create contacts during the sequence"
)
.
def
(
bp
::
self
==
bp
::
self
)
...
...
include/multicontact-api/scenario/contact-sequence.hpp
View file @
9663d4c4
...
...
@@ -743,6 +743,32 @@ struct ContactSequenceTpl : public serialization::Serializable<ContactSequenceTp
return
true
;
}
/**
* @brief haveRootTrajectories check that a root trajectory exist for each contact phases.
* Also check that it start and end at the correct time interval
* @return
*/
bool
haveRootTrajectories
()
const
{
size_t
i
=
0
;
for
(
const
ContactPhase
&
phase
:
m_contact_phases
){
if
(
!
phase
.
m_root
){
std
::
cout
<<
"Root trajectory not defined for phase : "
<<
i
<<
std
::
endl
;
return
false
;
}
if
(
phase
.
m_root
->
min
()
!=
phase
.
timeInitial
()){
std
::
cout
<<
"Root trajectory do not start at t_init for phase : "
<<
i
<<
std
::
endl
;
return
false
;
}
if
(
phase
.
m_root
->
max
()
!=
phase
.
timeFinal
()){
std
::
cout
<<
"Root trajectory do not start at t_final for phase : "
<<
i
<<
std
::
endl
;
return
false
;
}
++
i
;
}
return
true
;
}
/**
* @brief getAllEffectorsInContact return a vector of names of all the effectors used to create contacts during the sequence
* @return
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a 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