BipedalLocomotion::ML::MANNTrajectoryGenerator class

MANNTrajectoryGenerator is a class that uses MANNAutoregressive to generate a kinematically feasible trajectory for humanoid robots.

The planner will generate a trajectory which duration is equal to slow_down_factor * time_horizon seconds.

MANN trajectory generator

The diagram illustrates the utilization of the MANNAutoregressive within the MANNTrajectoryGenerator class.

Image

To initialize the generator, the user needs to set the initial state using the MANNTrajectoryGenerator::setInitialState method. The MANNTrajectoryGeneratorInput, provided by the user, serves as the input for the MANNAutoregressiveInput, along with the 'mergePointIndex.' The MANNAutoregressiveInput is assumed to remain constant within the trajectory horizon. The 'mergePointIndex' indicates the index at which the new trajectory will be attached. For example, when the MANNTrajectoryGenerator generates a trajectory consisting of 'N' points, if the 'mergePointIndex' is set to 3, the first three elements of the new trajectory will be derived from the previously computed trajectory by MANNTrajectoryGeneratorOutput, utilizing the previous MANNAutoregressiveInput. Subsequently, all points from 3 to N will be evaluated using the current MANNAutoregressiveInput. This behavior is facilitated by a mechanism that stores the autoregressive state required for resetting the MANNAutoregressive at the designated merge point. Every time the MANNAutoregressive::advance() function is invoked by the MANNTrajectoryGenerator, the autoregressive state is stored for future reference.

Base classes

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

Constructors, destructors, conversion operators

MANNTrajectoryGenerator()
Constructor.
~MANNTrajectoryGenerator()
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 trajectory planner.
auto setInput(const Input& input) -> bool override
Set the input to the planner model.
auto advance() -> bool override
Generate the trajectory.
auto isOutputValid() const -> bool override
Check if the output is valid.
auto getOutput() const -> const Output& override
Get the output from trajectory.
auto setInitialState(Eigen::Ref<const Eigen::VectorXd> jointPositions, const manif::SE3d& basePose) -> bool
Set the initial state of the planner.

Function documentation

bool BipedalLocomotion::ML::MANNTrajectoryGenerator::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::MANNTrajectoryGenerator::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) override

Initialize the trajectory planner.

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

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

Set the input to the planner model.

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

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

Generate the trajectory.

Returns true in case of success, false otherwise.

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

Check if the output is valid.

Returns true if the output is valid, false otherwise.

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

Get the output from trajectory.

Returns the output of the system.

bool BipedalLocomotion::ML::MANNTrajectoryGenerator::setInitialState(Eigen::Ref<const Eigen::VectorXd> jointPositions, const manif::SE3d& basePose)

Set the initial state of the planner.

Parameters
jointPositions position of the joints.
basePose pose of the base.