BaseEstimatorFromFootIMU class
BaseEstimatorFromFootIMU implements the propagation of the foot pose to the root link through the kinematic chain given by the leg joints positions.
This class assumes that the foot has a rectangular shape as shown in the following schematics
p2 __|__ p1 __ | | | | ___|__|__|___+ | FOOT | | | | LENGTH |__|__| __| p3 | p4
|_____| FOOT WIDTH
Base classes
- 
              template<class _Input, class _Output>class BipedalLocomotion::System::Advanceable<BaseEstimatorFromFootIMUInput, BaseEstimatorFromFootIMUState>
 - Basic class that represents a discrete system.
 
Public functions
- auto setModel(const iDynTree::Model& model) -> bool
 - Set the iDynTree::Model of the robot to be used by the estimator.
 - 
              auto initialize(std::weak_ptr<const ParametersHandler::
IParametersHandler> handler) -> bool override  - Initialize the BaseEstimatorFromFootIMU block.
 - auto setInput(const BaseEstimatorFromFootIMUInput& input) -> bool override
 - Set the input of the estimator.
 - auto advance() -> bool override
 - Perform one step of the estimator.
 - auto isOutputValid() const -> bool override
 - Check if the output of the estimator is valid.
 - auto getOutput() const -> const BaseEstimatorFromFootIMUState& override
 - Get the internal state of the BaseEstimatorFromFootIMU.
 - void setState(const BaseEstimatorFromFootIMUState& state)
 - Set the state of the BaseEstimatorFromFootIMU.
 
Function documentation
              bool BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: setModel(const iDynTree::Model& model)
            
            Set the iDynTree::Model of the robot to be used by the estimator.
| Parameters | |
|---|---|
| model | the model considered in the estimator | 
| Returns | true in case of success, false otherwise. | 
              bool BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: initialize(std::weak_ptr<const ParametersHandler:: IParametersHandler> handler) override
            
            Initialize the BaseEstimatorFromFootIMU block.
| Parameters | |
|---|---|
| handler | pointer to the parameter handler. | 
| Returns | true in case of success/false otherwise. | 
The setModel and setStanceFootRF methods must be called before initialization.
              bool BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: setInput(const BaseEstimatorFromFootIMUInput& input) override
            
            Set the input of the estimator.
| Parameters | |
|---|---|
| input | the input of the system. | 
| Returns | true in case of success, false otherwise. | 
              bool BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: advance() override
            
            Perform one step of the estimator.
| Returns | true in case of success, false otherwise. | 
|---|
The estimator must have been initialized first.
              bool BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: isOutputValid() const override
            
            Check if the output of the estimator is valid.
| Returns | true in case of success, false otherwise. | 
|---|
              const BaseEstimatorFromFootIMUState& BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: getOutput() const override
            
            Get the internal state of the BaseEstimatorFromFootIMU.
| Returns | a const reference to the state of the estimator. | 
|---|
              void BipedalLocomotion:: Estimators:: BaseEstimatorFromFootIMU:: setState(const BaseEstimatorFromFootIMUState& state)
            
            Set the state of the BaseEstimatorFromFootIMU.
| Parameters | |
|---|---|
| state | of the BaseEstimatorFromFootIMU |