AnymalStateEstimator
The state estimator for anymal.
anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ > Class Template Referenceabstract

Generic interface to be used for filters performing state estimation inside AnymalStateEstimator. More...

#include <AnymalFilter.hpp>

Inheritance diagram for anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >:
Inheritance graph

Public Types

using RobotModel = romo::RobotModel< ConcreteDescription_, RobotState_ >
 
using RD = typename RobotModel::RD
 
using CT = typename ConcreteDescription_::ConcreteTopology
 
using JointEnum = typename CT::JointEnum
 
using ContactEnum = typename CT::ContactEnum
 
using StateStatus = anymal_description::StateStatus
 
using PoseCovarianceMatrix = Eigen::Matrix< double, RD::getNumSpatialDof(), RD::getNumSpatialDof()>
 
using JointState = std_utils::EnumArray< JointEnum, any_measurements::ExtendedJointState >
 
template<typename ValueType_ >
using ContactEnumContainer = std_utils::EnumArray< ContactEnum, ValueType_ >
 

Public Member Functions

 AnymalFilter ()=delete
 
 AnymalFilter (any_node::Node::NodeHandlePtr nh)
 
virtual ~AnymalFilter ()=default
 
virtual bool initFilter (const kindr::HomTransformQuatD &poseBaseToOdom)=0
 
virtual bool resetFilter (const kindr::HomTransformQuatD &poseBaseToOdom)=0
 
virtual kindr::RotationQuaternionPD getOrientationBaseToWorld () const =0
 
virtual kindr::Velocity3D getLinearVelocityBaseInWorldFrame () const =0
 
virtual kindr::LocalAngularVelocityPD getAngularVelocityBaseInBaseFrame () const =0
 
virtual kindr::Position3D getPositionWorldToBaseInWorldFrame () const =0
 
virtual Eigen::Matrix< double, 3, 1 > getImuLinearAccelerationBias () const =0
 
virtual Eigen::Matrix< double, 3, 1 > getImuAngularVelocityBias () const =0
 
virtual PoseCovarianceMatrix getEstPoseInOdomCovariance () const =0
 
virtual PoseCovarianceMatrix getEstTwistCovariance () const =0
 
virtual any_measurements::Time getLastImuStamp () const =0
 
virtual StateStatus getStatus () const =0
 
virtual void processImuReadings (const any_measurements::ImuWithCovariance &imu)=0
 
virtual void processKinematics (const JointState &joints, const ContactEnumContainer< Contact > &contacts, const bool fakeKinematicsUpdateActive)=0
 
virtual void updateFilter ()=0
 
virtual void addVariablesToLog ()
 
virtual void setModelPtr (std::shared_ptr< RobotModel > modelPtr)
 
virtual void updateFullContactFlag (const bool hasFullContact)
 
any_measurements::Time getLastEstimatedStateStamp () const
 

Protected Attributes

any_node::Node::NodeHandlePtr nh_
 
Eigen::Vector3d previousAngularVelocityMeasurement_ = Eigen::Vector3d::Zero()
 
any_measurements::Time lastEstimatedStateStamp_
 
bool initialFullContactSet_ {false}
 

Detailed Description

template<typename ConcreteDescription_, typename RobotState_>
class anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >

Generic interface to be used for filters performing state estimation inside AnymalStateEstimator.

Template Parameters
ConcreteDescription_romo::ConcreteDescription
RobotState_romo::RobotState

Member Typedef Documentation

template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::ContactEnum = typename CT::ContactEnum
template<typename ConcreteDescription_ , typename RobotState_ >
template<typename ValueType_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::ContactEnumContainer = std_utils::EnumArray<ContactEnum, ValueType_>
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::CT = typename ConcreteDescription_::ConcreteTopology
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::JointEnum = typename CT::JointEnum
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::JointState = std_utils::EnumArray<JointEnum, any_measurements::ExtendedJointState>
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::PoseCovarianceMatrix = Eigen::Matrix<double, RD::getNumSpatialDof(), RD::getNumSpatialDof()>
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::RD = typename RobotModel::RD
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::RobotModel = romo::RobotModel<ConcreteDescription_, RobotState_>
template<typename ConcreteDescription_ , typename RobotState_ >
using anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::StateStatus = anymal_description::StateStatus

Constructor & Destructor Documentation

template<typename ConcreteDescription_ , typename RobotState_ >
anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::AnymalFilter ( )
delete
template<typename ConcreteDescription_ , typename RobotState_ >
anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::AnymalFilter ( any_node::Node::NodeHandlePtr  nh)
inlineexplicit
template<typename ConcreteDescription_ , typename RobotState_ >
virtual anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::~AnymalFilter ( )
virtualdefault

Member Function Documentation

template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::addVariablesToLog ( )
inlinevirtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual kindr::LocalAngularVelocityPD anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getAngularVelocityBaseInBaseFrame ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual PoseCovarianceMatrix anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getEstPoseInOdomCovariance ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual PoseCovarianceMatrix anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getEstTwistCovariance ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual Eigen::Matrix<double, 3, 1> anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getImuAngularVelocityBias ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual Eigen::Matrix<double, 3, 1> anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getImuLinearAccelerationBias ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
any_measurements::Time anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getLastEstimatedStateStamp ( ) const
inline
template<typename ConcreteDescription_ , typename RobotState_ >
virtual any_measurements::Time anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getLastImuStamp ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual kindr::Velocity3D anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getLinearVelocityBaseInWorldFrame ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual kindr::RotationQuaternionPD anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getOrientationBaseToWorld ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual kindr::Position3D anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getPositionWorldToBaseInWorldFrame ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual StateStatus anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::getStatus ( ) const
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual bool anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::initFilter ( const kindr::HomTransformQuatD &  poseBaseToOdom)
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::processImuReadings ( const any_measurements::ImuWithCovariance &  imu)
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::processKinematics ( const JointState joints,
const ContactEnumContainer< Contact > &  contacts,
const bool  fakeKinematicsUpdateActive 
)
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual bool anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::resetFilter ( const kindr::HomTransformQuatD &  poseBaseToOdom)
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::setModelPtr ( std::shared_ptr< RobotModel modelPtr)
inlinevirtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::updateFilter ( )
pure virtual
template<typename ConcreteDescription_ , typename RobotState_ >
virtual void anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::updateFullContactFlag ( const bool  hasFullContact)
inlinevirtual

Member Data Documentation

template<typename ConcreteDescription_ , typename RobotState_ >
bool anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::initialFullContactSet_ {false}
protected
template<typename ConcreteDescription_ , typename RobotState_ >
any_measurements::Time anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::lastEstimatedStateStamp_
protected
template<typename ConcreteDescription_ , typename RobotState_ >
any_node::Node::NodeHandlePtr anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::nh_
protected
template<typename ConcreteDescription_ , typename RobotState_ >
Eigen::Vector3d anymal_state_estimator::AnymalFilter< ConcreteDescription_, RobotState_ >::previousAngularVelocityMeasurement_ = Eigen::Vector3d::Zero()
protected

The documentation for this class was generated from the following file: