struct
AutoregressiveStateAutoregressiveState contains all quantities required to reset the Advanceable The base position trajectory, base 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 base direction (along with its orthogonal vector).
Public static functions
- static auto generateDummyAutoregressiveState(const VelMANNInput& input, const VelMANNOutput& output, const manif::SE3d& I_H_B, const VelMANNFootState& leftFootState, const VelMANNFootState& rightFootState, int mocapFrameRate, const std::chrono::nanoseconds& pastProjectedBaseHorizon) -> AutoregressiveState
- Generate a dummy autoregressive state from the input.
Public variables
- VelMANNOutput previousVelMannOutput
- Output of the VelMANN network generated at the previous iteration.
- VelMANNInput previousVelMannInput
- Input to the VelMANN network at previous iteration.
- manif::SE3d I_H_B_prev
- SE(3) transformation of the base direction respect to the inertial frame.
- std::deque<Eigen::Vector3d> pastProjectedBaseVelocity
- Past base linear velocity, Each element of the deque contains the x, y, and z velocity.
- std::deque<Eigen::Vector3d> pastProjectedBaseAngVelocity
- Past base angular velocity, Each element of the deque contains x, y, and z angular velocity.
- VelMANNFootState leftFootState
- Left foot state.
- VelMANNFootState rightFootState
- Right foot state.
- manif::SE3d I_H_B
- SE(3) transformation of the base with 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.
- Eigen::Vector2d I_x_des
- SE(3) transformation of the input reference base with respect to the inertial frame.
- manif::SE3d I_H_ref
- SE(3) transformation of the input reference base with respect to the inertial frame.
Function documentation
static AutoregressiveState BipedalLocomotion:: ML:: VelMANNAutoregressive:: AutoregressiveState:: generateDummyAutoregressiveState(const VelMANNInput& input,
const VelMANNOutput& output,
const manif::SE3d& I_H_B,
const VelMANNFootState& leftFootState,
const VelMANNFootState& 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. |
Variable documentation
std::chrono::nanoseconds BipedalLocomotion:: ML:: VelMANNAutoregressive:: AutoregressiveState:: time
Current time stored in the advanceable.
For the linear PID
Eigen::Vector2d BipedalLocomotion:: ML:: VelMANNAutoregressive:: AutoregressiveState:: I_x_des
SE(3) transformation of the input reference base with respect to the inertial frame.
For the rotational PID