BipedalLocomotion::ML::MANNAutoregressive class

MANNAutoregressive is a class that allows to perform autoregressive inference with Mode-Adaptive Neural Networks (MANN).

MANN Autoregressive

The following diagram shows how the MANN network is used inside the MANNAutoregressive class. The output of MANN is given to two blocks, one computes the kinematically feasible base position, while the other blends it to te input provided by the user

Image

Base classes

template<class _Input, class _Output>
class BipedalLocomotion::System::Advanceable<MANNAutoregressiveInput, MANNAutoregressiveOutput>
Basic class that represents a discrete system.

Public types

struct AutoregressiveState
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.

Constructors, destructors, conversion operators

MANNAutoregressive()
Constructor.
~MANNAutoregressive()
Destructor.

Public functions

auto setRobotModel(const iDynTree::Model& model) -> bool
Set the robot model.
auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) -> bool override
Initialize the network.
auto setInput(const Input& input) -> bool override
Set the input to the autoregressive model.
auto advance() -> bool override
Perform one step of the autoregressive model.
auto reset(const MANNInput& input, const Contacts::EstimatedContact& leftFoot, const Contacts::EstimatedContact& rightFoot, const manif::SE3d& basePose, const manif::SE3Tangentd& baseVelocity) -> bool
Reset the autoregressive model.
auto reset(const MANNInput& input, const Contacts::EstimatedContact& leftFoot, const Math::SchmittTriggerState& leftFootSchimittTriggerState, const Contacts::EstimatedContact& rightFoot, const Math::SchmittTriggerState& rightFootSchimittTriggerState, const manif::SE3d& basePosition, const manif::SE3Tangentd& baseVelocity, const AutoregressiveState& autoregressiveState, const std::chrono::nanoseconds& time) -> bool
Reset the autoregressive model.
auto isOutputValid() const -> bool override
Check if the output is valid.
auto getOutput() const -> const Output& override
Get the output from MANNAutoregressive.
auto getMANNInput() const -> const MANNInput&
Get the structure that has been used as input for MANN.
auto getAutoregressiveState() const -> const AutoregressiveState&
Get the autoregressive state required to rest MANNAutoregressive.

Function documentation

bool BipedalLocomotion::ML::MANNAutoregressive::setRobotModel(const iDynTree::Model& model)

Set the robot model.

Parameters
model model of the robot considered by the network. Please load the very same model with the same joint serialization used to train the MANN network.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) override

Initialize the network.

Parameters
paramHandler pointer to the parameters handler.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::setInput(const Input& input) override

Set the input to the autoregressive model.

Parameters
input input to the model
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::advance() override

Perform one step of the autoregressive model.

Returns true in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::reset(const MANNInput& input, const Contacts::EstimatedContact& leftFoot, const Contacts::EstimatedContact& rightFoot, const manif::SE3d& basePose, const manif::SE3Tangentd& baseVelocity)

Reset the autoregressive model.

Parameters
input raw mann input.
leftFoot state of the left foot.
rightFoot state of the right foot.
basePose
baseVelocity current base velocity expressed in mixed representation.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::reset(const MANNInput& input, const Contacts::EstimatedContact& leftFoot, const Math::SchmittTriggerState& leftFootSchimittTriggerState, const Contacts::EstimatedContact& rightFoot, const Math::SchmittTriggerState& rightFootSchimittTriggerState, const manif::SE3d& basePosition, const manif::SE3Tangentd& baseVelocity, const AutoregressiveState& autoregressiveState, const std::chrono::nanoseconds& time)

Reset the autoregressive model.

Parameters
input raw mann input.
leftFoot state of the left foot.
leftFootSchimittTriggerState
rightFoot state of the right foot.
rightFootSchimittTriggerState
basePosition current base position.
baseVelocity current base velocity expressed in mixed representation.
autoregressiveState the autoregressive state at which you want to reset your model.
time time used to reset the system
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ML::MANNAutoregressive::isOutputValid() const override

Check if the output is valid.

Returns true if the output is valid, false otherwise.

const Output& BipedalLocomotion::ML::MANNAutoregressive::getOutput() const override

Get the output from MANNAutoregressive.

Returns the output of the system.

const MANNInput& BipedalLocomotion::ML::MANNAutoregressive::getMANNInput() const

Get the structure that has been used as input for MANN.

Returns the MANNInput

const AutoregressiveState& BipedalLocomotion::ML::MANNAutoregressive::getAutoregressiveState() const

Get the autoregressive state required to rest MANNAutoregressive.

Returns the AutoregressiveState