class
VelMANNTrajectoryGeneratorVelMANNTrajectoryGenerator is a class that uses VelMANNAutoregressive 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. This class differs from the MANNTrajectoryGenerator class in that the input and output features of the learned model are velocity-based rather than position-based. The postprocessing, using the 3D velocity output features of the learned model, allows more modularity in the trajectory generation. More details are available in the paper mentioned below.
VelMANN trajectory generator
The diagram illustrates the utilization of the VelMANNAutoregressive within the VelMANNTrajectoryGenerator class. To initialize the generator, the user needs to set the initial state using the VelMANNTrajectoryGenerator::
Base classes
-
template<class _Input, class _Output>class BipedalLocomotion::System::Advanceable<VelMANNTrajectoryGeneratorInput, VelMANNTrajectoryGeneratorOutput>
- Basic class that represents a discrete system.
Constructors, destructors, conversion operators
- VelMANNTrajectoryGenerator()
- Constructor.
- ~VelMANNTrajectoryGenerator()
- 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:: VelMANNTrajectoryGenerator:: 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 VelMANN network. |
Returns | true in case of success, false otherwise. |
bool BipedalLocomotion:: ML:: VelMANNTrajectoryGenerator:: 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:: VelMANNTrajectoryGenerator:: 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:: VelMANNTrajectoryGenerator:: advance() override
Generate the trajectory.
Returns | true in case of success, false otherwise. |
---|
bool BipedalLocomotion:: ML:: VelMANNTrajectoryGenerator:: isOutputValid() const override
Check if the output is valid.
Returns | true if the output is valid, false otherwise. |
---|
const Output& BipedalLocomotion:: ML:: VelMANNTrajectoryGenerator:: getOutput() const override
Get the output from trajectory.
Returns | the output of the system. |
---|
bool BipedalLocomotion:: ML:: VelMANNTrajectoryGenerator:: 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. |