class
GyroscopeMeasurementDynamicsThe GyroscopeMeasurementDynamics class is a concrete implementation of the Dynamics.
Please use this element if you want to use the model dynamics of a gyroscope. The GyroscopeMeasurementDynamics represents the following equation in the continuous time:
where the joint velocity is estimated by the ukf.
Base classes
Constructors, destructors, conversion operators
Public functions
-
auto initialize(std::weak_ptr<const ParametersHandler::
IParametersHandler> paramHandler, const std::string& name) -> bool override - Initialize the state dynamics.
-
auto finalize(const System::
VariablesHandler& stateVariableHandler) -> bool override - Finalize the Dynamics.
- auto setSubModels(const std::vector<SubModel>& subModelList, const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList) -> bool override
- Set the KinDynWrapper object.
- auto checkStateVariableHandler() -> bool override
- Controls whether the variable handler contains the variables on which the dynamics depend.
- auto update() -> bool override
- Update the content of the element.
- void setState(const Eigen::Ref<const Eigen::VectorXd> ukfState) override
- Set the state of the ukf needed to update the dynamics of the measurement variable associated to ths object.
- void setInput(const UKFInput& ukfInput) override
- Set a
UKFInput
object.
Function documentation
bool BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: initialize(std::weak_ptr<const ParametersHandler:: IParametersHandler> paramHandler,
const std::string& name) override
Initialize the state dynamics.
Parameters | |
---|---|
paramHandler | pointer to the parameters handler. |
name | name of the dynamics. |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: finalize(const System:: VariablesHandler& stateVariableHandler) override
Finalize the Dynamics.
Parameters | |
---|---|
stateVariableHandler | object describing the variables in the state vector. |
Returns | true in case of success, false otherwise. |
bool BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: setSubModels(const std::vector<SubModel>& subModelList,
const std::vector<std::shared_ptr<KinDynWrapper>>& kinDynWrapperList) override
Set the KinDynWrapper object.
Parameters | |
---|---|
subModelList | list of SubModel objects |
kinDynWrapperList | list of pointers to KinDynWrapper objects. |
Returns | True in case of success, false otherwise. |
bool BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: checkStateVariableHandler() override
Controls whether the variable handler contains the variables on which the dynamics depend.
Returns | True in case all the dependencies are contained in the variable handler, false otherwise. |
---|
bool BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: update() override
Update the content of the element.
Returns | True in case of success, false otherwise. |
---|
void BipedalLocomotion:: Estimators:: RobotDynamicsEstimator:: GyroscopeMeasurementDynamics:: setState(const Eigen::Ref<const Eigen::VectorXd> ukfState) override
Set the state of the ukf needed to update the dynamics of the measurement variable associated to ths object.
Parameters | |
---|---|
ukfState | reference to the ukf state. |