BipedalLocomotion::ML::MANNAutoregressive::AutoregressiveState struct

AutoregressiveState contains all quantities required to reset the Advanceable The base position trajectory, facing direction trajectory and base velocity trajectories are written in a bidimensional local reference frame L in which we assume all the quantities related to the ground-projected base trajectory in xi and yi to be expressed.

At each step ti, L is defined to have its origin in the current ground-projected robot base position and orientation defined by the current facing direction (along with its orthogonal vector).

Public static functions

static auto generateDummyAutoregressiveState(const MANNInput& input, const MANNOutput& output, const manif::SE3d& I_H_B, const MANNFootState& leftFootState, const MANNFootState& rightFootState, int mocapFrameRate, const std::chrono::nanoseconds& pastProjectedBaseHorizon) -> AutoregressiveState
Generate a dummy autoregressive state from the input.

Public variables

MANNOutput previousMANNOutput
Output of the MANN network generated at the previous iteration.
MANNInput previousMANNInput
Input to the MANN network at previous iteration.
manif::SE2d I_H_FD
SE(2) transformation of the facing direction respect to the inertial frame.
std::deque<Eigen::Vector2d> pastProjectedBasePositions
Past projected base position, Each element of the deque contains the x and y position projected into the ground.
std::deque<Eigen::Vector2d> pastFacingDirection
Past projected facing direction, Each element of the deque contains the x and y direction projected into the ground.
std::deque<Eigen::Vector2d> pastProjectedBaseVelocity
Past projected base velocity, Each element of the deque contains the x and y velocity projected into the ground.
MANNFootState leftFootState
Left foot state.
MANNFootState rightFootState
Right foot state.
manif::SE3d I_H_B
SE(3) transformation of the base respect to the inertial frame.
SupportFoot supportFoot
Support foot.
Eigen::Vector3d projectedContactPositionInWorldFrame
Projected contact position in world frame.
int supportCornerIndex
Index of the support corner.
std::chrono::nanoseconds time
Current time stored in the advanceable.

Function documentation

static AutoregressiveState BipedalLocomotion::ML::MANNAutoregressive::AutoregressiveState::generateDummyAutoregressiveState(const MANNInput& input, const MANNOutput& output, const manif::SE3d& I_H_B, const MANNFootState& leftFootState, const MANNFootState& rightFootState, int mocapFrameRate, const std::chrono::nanoseconds& pastProjectedBaseHorizon)

Generate a dummy autoregressive state from the input.

Parameters
input input to the autoregressive model.
output output of the autoregressive model.
I_H_B SE(3) transformation of the base respect to the inertial frame.
leftFootState left foot state.
rightFootState right foot state.
mocapFrameRate frame rate of the mocap data.
pastProjectedBaseHorizon number of samples of the past base horizon considered in the neural network.
Returns A dummy AutoregressiveState.