struct
#include <BipedalLocomotion/ML/MANN.h>
MANNInput MANNInput contains the input to the MANN network.
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 variables
- Eigen::Matrix2Xd basePositionTrajectory
- Matrix containing the base position trajectory.
- Eigen::Matrix2Xd facingDirectionTrajectory
- Matrix containing the facing direction trajectory.
- Eigen::Matrix2Xd baseVelocitiesTrajectory
- Matrix containing the base velocity trajectory.
- Eigen::VectorXd jointPositions
- Vector containing the actual joint position in radians.
- Eigen::VectorXd jointVelocities
- Vector containing the actual joint velocity in radians per seconds.
Variable documentation
Eigen::Matrix2Xd BipedalLocomotion:: ML:: MANNInput:: basePositionTrajectory
Matrix containing the base position trajectory.
The rows contain the x and y position projected into the ground while the columns the position at each time instant.
Eigen::Matrix2Xd BipedalLocomotion:: ML:: MANNInput:: facingDirectionTrajectory
Matrix containing the facing direction trajectory.
The rows contain the x and y direction projected into the ground while the columns the direction at each time instant.
Eigen::Matrix2Xd BipedalLocomotion:: ML:: MANNInput:: baseVelocitiesTrajectory
Matrix containing the base velocity trajectory.
The rows contain the x and y velocity projected into the ground while the columns the position at each time instant.