Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
Q
quadruped-reactive-walking
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Gepetto
quadruped-reactive-walking
Commits
c4ec4773
Commit
c4ec4773
authored
2 years ago
by
Pierre-Alexandre Leziart
Browse files
Options
Downloads
Patches
Plain Diff
Fix computation of alphaVelocity in Estimator
parent
ba7c3bdf
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
include/qrw/Estimator.hpp
+5
-1
5 additions, 1 deletion
include/qrw/Estimator.hpp
python/Estimator.cpp
+1
-0
1 addition, 0 deletions
python/Estimator.cpp
src/Estimator.cpp
+42
-9
42 additions, 9 deletions
src/Estimator.cpp
with
48 additions
and
10 deletions
include/qrw/Estimator.hpp
+
5
−
1
View file @
c4ec4773
...
@@ -102,6 +102,8 @@ class Estimator {
...
@@ -102,6 +102,8 @@ class Estimator {
Matrix3
gethRb
()
{
return
hRb_
;
}
Matrix3
gethRb
()
{
return
hRb_
;
}
Vector3
getoTh
()
{
return
oTh_
;
}
Vector3
getoTh
()
{
return
oTh_
;
}
double
computeAlphaVelocity
();
private
:
private
:
////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////
///
///
...
@@ -179,7 +181,7 @@ class Estimator {
...
@@ -179,7 +181,7 @@ class Estimator {
/// \return alpha
/// \return alpha
///
///
////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////
double
computeAlphaVelocity
();
//
double computeAlphaVelocity();
////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////
///
///
...
@@ -212,6 +214,7 @@ class Estimator {
...
@@ -212,6 +214,7 @@ class Estimator {
bool
solo3D_
;
// Perfect estimator including yaw angle
bool
solo3D_
;
// Perfect estimator including yaw angle
double
dt_
;
// Time step of the estimator
double
dt_
;
// Time step of the estimator
double
dt_mpc_
;
// Time step of the mpc
double
dt_mpc_
;
// Time step of the mpc
int
k_mpc_
;
// Number of wbc time steps for each MPC time step
bool
initialized_
;
// Is intiialized after the first update of the IMU
bool
initialized_
;
// Is intiialized after the first update of the IMU
Vector4
feetFrames_
;
// Frame indexes of the four feet
Vector4
feetFrames_
;
// Frame indexes of the four feet
double
footRadius_
;
// radius of a foot
double
footRadius_
;
// radius of a foot
...
@@ -231,6 +234,7 @@ class Estimator {
...
@@ -231,6 +234,7 @@ class Estimator {
Vector12
vActuators_
;
// Measured velocities of actuators
Vector12
vActuators_
;
// Measured velocities of actuators
int
phaseRemainingDuration_
;
// Number of iterations left for the current gait phase
int
phaseRemainingDuration_
;
// Number of iterations left for the current gait phase
double
minElapsed_
;
// Minimum non zeros coefficients of feetStancePhaseDuration_
Vector4
feetStancePhaseDuration_
;
// Number of loops during which each foot has been in contact
Vector4
feetStancePhaseDuration_
;
// Number of loops during which each foot has been in contact
Vector4
feetStatus_
;
// Contact status of the four feet
Vector4
feetStatus_
;
// Contact status of the four feet
Matrix34
feetTargets_
;
// Target positions of the four feet
Matrix34
feetTargets_
;
// Target positions of the four feet
...
...
This diff is collapsed.
Click to expand it.
python/Estimator.cpp
+
1
−
0
View file @
c4ec4773
...
@@ -38,6 +38,7 @@ struct EstimatorVisitor : public bp::def_visitor<EstimatorVisitor<Estimator>> {
...
@@ -38,6 +38,7 @@ struct EstimatorVisitor : public bp::def_visitor<EstimatorVisitor<Estimator>> {
.
def
(
"get_oRh"
,
&
Estimator
::
getoRh
,
""
)
.
def
(
"get_oRh"
,
&
Estimator
::
getoRh
,
""
)
.
def
(
"get_hRb"
,
&
Estimator
::
gethRb
,
""
)
.
def
(
"get_hRb"
,
&
Estimator
::
gethRb
,
""
)
.
def
(
"get_oTh"
,
&
Estimator
::
getoTh
,
""
)
.
def
(
"get_oTh"
,
&
Estimator
::
getoTh
,
""
)
.
def
(
"get_alpha"
,
&
Estimator
::
computeAlphaVelocity
,
""
)
.
def
(
"run"
,
&
Estimator
::
run
,
.
def
(
"run"
,
&
Estimator
::
run
,
bp
::
args
(
"gait"
,
"goals"
,
"baseLinearAcceleration"
,
"baseAngularVelocity"
,
"baseOrientation"
,
"q_mes"
,
bp
::
args
(
"gait"
,
"goals"
,
"baseLinearAcceleration"
,
"baseAngularVelocity"
,
"baseOrientation"
,
"q_mes"
,
...
...
This diff is collapsed.
Click to expand it.
src/Estimator.cpp
+
42
−
9
View file @
c4ec4773
...
@@ -12,6 +12,7 @@ Estimator::Estimator()
...
@@ -12,6 +12,7 @@ Estimator::Estimator()
solo3D_
(
false
),
solo3D_
(
false
),
dt_
(
0.0
),
dt_
(
0.0
),
dt_mpc_
(
0.0
),
dt_mpc_
(
0.0
),
k_mpc_
(
0
),
initialized_
(
false
),
initialized_
(
false
),
feetFrames_
(
Vector4
::
Zero
()),
feetFrames_
(
Vector4
::
Zero
()),
footRadius_
(
0.155
),
footRadius_
(
0.155
),
...
@@ -27,6 +28,7 @@ Estimator::Estimator()
...
@@ -27,6 +28,7 @@ Estimator::Estimator()
qActuators_
(
Vector12
::
Zero
()),
qActuators_
(
Vector12
::
Zero
()),
vActuators_
(
Vector12
::
Zero
()),
vActuators_
(
Vector12
::
Zero
()),
phaseRemainingDuration_
(
0
),
phaseRemainingDuration_
(
0
),
minElapsed_
(
0.
),
feetStancePhaseDuration_
(
Vector4
::
Zero
()),
feetStancePhaseDuration_
(
Vector4
::
Zero
()),
feetStatus_
(
Vector4
::
Zero
()),
feetStatus_
(
Vector4
::
Zero
()),
feetTargets_
(
Matrix34
::
Zero
()),
feetTargets_
(
Matrix34
::
Zero
()),
...
@@ -62,8 +64,8 @@ void Estimator::initialize(Params& params) {
...
@@ -62,8 +64,8 @@ void Estimator::initialize(Params& params) {
solo3D_
=
params
.
solo3D
;
solo3D_
=
params
.
solo3D
;
// Filtering estimated linear velocity
// Filtering estimated linear velocity
int
k_mpc
=
(
int
)(
std
::
round
(
params
.
dt_mpc
/
params
.
dt_wbc
));
k_mpc
_
=
(
int
)(
std
::
round
(
params
.
dt_mpc
/
params
.
dt_wbc
));
windowSize_
=
(
int
)(
k_mpc
*
params
.
gait
.
rows
()
/
params
.
N_periods
);
windowSize_
=
(
int
)(
k_mpc
_
*
params
.
gait
.
rows
()
/
params
.
N_periods
);
vx_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
vx_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
vy_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
vy_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
vz_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
vz_queue_
.
resize
(
windowSize_
,
0.0
);
// List full of 0.0
...
@@ -146,12 +148,43 @@ void Estimator::updatFeetStatus(MatrixN const& gait, MatrixN const& feetTargets)
...
@@ -146,12 +148,43 @@ void Estimator::updatFeetStatus(MatrixN const& gait, MatrixN const& feetTargets)
feetStatus_
=
gait
.
row
(
0
);
feetStatus_
=
gait
.
row
(
0
);
feetTargets_
=
feetTargets
;
feetTargets_
=
feetTargets
;
// Update nb of iterations since contact for each foot
feetStancePhaseDuration_
+=
feetStatus_
;
feetStancePhaseDuration_
+=
feetStatus_
;
feetStancePhaseDuration_
=
feetStancePhaseDuration_
.
cwiseProduct
(
feetStatus_
);
feetStancePhaseDuration_
=
feetStancePhaseDuration_
.
cwiseProduct
(
feetStatus_
);
phaseRemainingDuration_
=
1
;
// Get minimum non-zero number of iterations since contact
while
(
feetStatus_
.
isApprox
((
Vector4
)
gait
.
row
(
phaseRemainingDuration_
)))
{
minElapsed_
=
0.
;
phaseRemainingDuration_
++
;
for
(
int
j
=
0
;
j
<
4
;
j
++
)
{
if
(
feetStancePhaseDuration_
(
j
)
>
0
)
{
minElapsed_
=
minElapsed_
==
0
?
feetStancePhaseDuration_
(
j
)
:
std
::
min
(
feetStancePhaseDuration_
(
j
),
minElapsed_
);
}
}
// Get minimum number of MPC iterations remaining among all feet in contact
phaseRemainingDuration_
=
std
::
numeric_limits
<
int
>::
max
();
bool
flying
=
true
;
for
(
int
j
=
0
;
j
<
4
;
j
++
)
{
if
(
feetStatus_
(
j
)
==
0.
)
{
continue
;
}
flying
=
false
;
int
i
=
1
;
while
(
i
<
gait
.
rows
()
&&
gait
(
i
,
j
)
==
1.
)
{
i
++
;
}
if
(
i
<
phaseRemainingDuration_
)
{
phaseRemainingDuration_
=
i
;
}
}
if
(
flying
)
{
phaseRemainingDuration_
=
0
;
}
// Convert minimum number of MPC iterations into WBC iterations
if
(
phaseRemainingDuration_
!=
0
)
{
int
a
=
static_cast
<
int
>
(
std
::
round
(
minElapsed_
))
%
k_mpc_
;
phaseRemainingDuration_
=
a
==
0
?
(
phaseRemainingDuration_
-
1
)
*
k_mpc_
:
phaseRemainingDuration_
*
k_mpc_
-
a
;
}
}
}
}
...
@@ -237,11 +270,11 @@ void Estimator::computeFeetPositionBarycenter() {
...
@@ -237,11 +270,11 @@ void Estimator::computeFeetPositionBarycenter() {
}
}
double
Estimator
::
computeAlphaVelocity
()
{
double
Estimator
::
computeAlphaVelocity
()
{
double
a
=
std
::
ceil
(
feetStancePhaseDuration_
.
maxCoeff
()
*
(
dt_
/
dt_mpc_
))
-
1
;
double
a
=
minElapsed_
;
double
b
=
static_cast
<
double
>
(
phaseRemainingDuration_
);
double
b
=
static_cast
<
double
>
(
phaseRemainingDuration_
);
double
c
=
((
a
+
b
)
-
2
)
*
0.5
;
const
double
n
=
2
*
k_mpc_
;
// Nb of steps of margin around contact switch
const
double
n
=
2
;
// Nb of steps of margin around contact switch
double
c
=
(
a
+
b
)
*
0.5
-
n
;
if
(
a
<=
(
n
-
1
)
||
b
<=
n
||
std
::
abs
(
c
-
(
a
-
n
))
<=
n
)
if
(
a
<=
n
||
b
<=
n
)
return
alphaVelMax_
;
return
alphaVelMax_
;
else
else
return
alphaVelMin_
+
(
alphaVelMax_
-
alphaVelMin_
)
*
std
::
abs
(
c
-
(
a
-
n
))
/
c
;
return
alphaVelMin_
+
(
alphaVelMax_
-
alphaVelMin_
)
*
std
::
abs
(
c
-
(
a
-
n
))
/
c
;
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
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!
Save comment
Cancel
Please
register
or
sign in
to comment