BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator class

RobotDynamicsEstimator is a concrete class and implements a robot dynamics estimator.

The estimator is here implemented as an Unscented Kalman Filter. The user can build the estimator by using the build method or can initialize the RobotDynamicsEstimator object and then create the UkfState model and UkfMeasurement model which are then passed to the bfl::UKFPrediction and bfl::UKFCorrection objects respectively. To run an estimation step the user should set the input using setInput, call the advance method to perform an estimation step, use getOutput to get the estimation result.

Base classes

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

Public static functions

static auto build(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, std::shared_ptr<iDynTree::KinDynComputations> kinDynFullModel, const std::vector<SubModel>& subModelList, const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList) -> std::unique_ptr<RobotDynamicsEstimator>
build a robot dynamics estimator implementing an unscented kalman filter.

Constructors, destructors, conversion operators

RobotDynamicsEstimator()
Constructor.
~RobotDynamicsEstimator() virtual
Destructor.

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) -> bool override
Initialize the RobotDynamicsEstimator.
auto finalize(const System::VariablesHandler& stateVariableHandler, const System::VariablesHandler& measurementVariableHandler, std::shared_ptr<iDynTree::KinDynComputations> kinDynFullModel) -> bool
Finalize the estimator.
auto setInitialState(const RobotDynamicsEstimatorOutput& initialState) -> bool
set the initial state of the estimator.
auto isOutputValid() const -> bool override
Determines the validity of the object retrieved with getOutput()
auto advance() -> bool override
Advance the internal state.
auto setInput(const RobotDynamicsEstimatorInput& input) -> bool override
Set the input for the estimator.
auto getOutput() const -> const RobotDynamicsEstimatorOutput& override
Get the output of the ukf.

Function documentation

static std::unique_ptr<RobotDynamicsEstimator> BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::build(std::weak_ptr<const ParametersHandler::IParametersHandler> handler, std::shared_ptr<iDynTree::KinDynComputations> kinDynFullModel, const std::vector<SubModel>& subModelList, const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList)

build a robot dynamics estimator implementing an unscented kalman filter.

Parameters
handler pointer to the IParametersHandler interface.
kinDynFullModel a pointer to an iDynTree::KinDynComputations object that will be shared among all the dynamics.
subModelList a list of SubModel objects
kinDynWrapperList a list of pointers to a KinDynWrapper objects that will be shared among all the dynamics
Returns a RobotDynamicsEstimator. In case of issues an invalid RobotDynamicsEstimator will be returned.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) override

Initialize the RobotDynamicsEstimator.

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

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::finalize(const System::VariablesHandler& stateVariableHandler, const System::VariablesHandler& measurementVariableHandler, std::shared_ptr<iDynTree::KinDynComputations> kinDynFullModel)

Finalize the estimator.

Parameters
stateVariableHandler reference to a System::VariablesHandler object describing the ukf state.
measurementVariableHandler reference to a System::VariablesHandler object describing the ukf measurement.
kinDynFullModel a pointer to an iDynTree::KinDynComputations object.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::setInitialState(const RobotDynamicsEstimatorOutput& initialState)

set the initial state of the estimator.

Parameters
initialState a reference to an Output object.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::isOutputValid() const override

Determines the validity of the object retrieved with getOutput()

Returns True if the object is valid, false otherwise.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::advance() override

Advance the internal state.

Returns True if the advance is successfull.

This may change the value retrievable from getOutput().

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::setInput(const RobotDynamicsEstimatorInput& input) override

Set the input for the estimator.

Parameters
input is a struct containing the input of the estimator.

const RobotDynamicsEstimatorOutput& BipedalLocomotion::Estimators::RobotDynamicsEstimator::RobotDynamicsEstimator::getOutput() const override

Get the output of the ukf.

Returns A struct containing the ukf estimation result.