C++ API and example

1. Introduction

This page exist in order to extract the examples from the Doxygen documentation, Please have look at the end of this page there are all the examples.

2. C++ API and example

class BaseEkfWithImuKin

Extended Kalman Filter implementation for base state estimation using the imu and the kinematics information.

Details:

Todo:

explain here the math around the EKF

Public Functions

BaseEkfWithImuKin()

Construct a new Base Ekf With Imu and Kinematics object.

~BaseEkfWithImuKin()

Destroy the Base Ekf With Imu Kin object.

void initialize(const BaseEkfWithImuKinSettings &settings)

Get the EKF settings and initialize the filter from them.

Parameters:

settings

void set_initial_state(Eigen::Ref<const Eigen::Vector3d> base_position, const Eigen::Quaterniond &base_attitude, Eigen::Ref<const Eigen::Vector3d> base_linear_velocity, Eigen::Ref<const Eigen::Vector3d> base_angular_velocity)

Set initial state.

Parameters:
  • base_position – Base position with respect to the world frame.

  • base_attitude – Base orientation with respect to the world frame.

  • base_linear_velocity – Base linear velocity with respect to the base frame.

  • base_angular_velocity – Base angular velocity with respect to the base frame.

void set_initial_state(Eigen::Ref<const Eigen::Matrix<double, 7, 1>> base_se3_position, Eigen::Ref<const Eigen::Matrix<double, 6, 1>> base_se3_velocity)

Set initial state.

Parameters:
  • base_se3_position – [XYZ Quaternion] SE3 representation of the base position with respect to the world frame.

  • base_se3_velocity – [Linear Angular] base velocity in the base frame.

void update_filter(const std::vector<bool> &contact_schedule, Eigen::Ref<const Eigen::Vector3d> imu_accelerometer, Eigen::Ref<const Eigen::Vector3d> imu_gyroscope, Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity)

Feed in the sensor raw data from the robot and update the filter output.

Parameters:
  • contact_schedule – vector of boolean, if one boolean is true it means that the corresponding end-effector is in contact.

  • imu_accelerometer – imu raw accelerometer data.

  • imu_gyroscope – imu raw gyroscope data.

  • joint_position – joint position data (in pinocchio ordering).

  • joint_velocity – joint velocity data (in pinocchio ordering).

void get_filter_output(Eigen::Ref<Eigen::VectorXd> robot_configuration, Eigen::Ref<Eigen::VectorXd> robot_velocity)

Get the filter output which is the robot state.

Parameters:
  • robot_configuration

  • robot_velocity

const std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> &get_measurement()

Get measurement.

Parameters:

root_velocities

Private Functions

void compute_end_effectors_forward_kinematics(Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity)

Compute the base/imu velocities.

void integrate_process_model(Eigen::Ref<const Eigen::Vector3d> imu_accelerometer, Eigen::Ref<const Eigen::Vector3d> imu_gyroscope)

Integrate the process model using the imu data.

compute mu_pre.

void compute_discrete_prediction_jacobian()

Fill in the process jacobians (cont_proc_jac_, disc_proc_jac_).

void compute_noise_jacobian()

Fill in the noise jacobian.

void construct_continuous_noise_covariance()

Use and additive white noise as continuous noise.

void construct_discrete_noise_covariance()

Discretise the noise covariance using zero-order hold and truncating higher-order terms.

void construct_discrete_measurement_noise_covariance()

Discretise the measurement noise covariance.

void prediction_step()

Propagate the state covariance (predicted_state_.covariance).

void measurement_model(const std::vector<bool> &contact_schedule, Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity)

Use the kinematics to measure the linear velocity of the base.

Parameters:
  • contact_schedule – This indicates which end-effector is currently in contact.

  • joint_position – joint positions.

  • joint_velocity – joint velocities.

void update_step(const std::vector<bool> &contact_schedule, Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity)

Update the current state posterior_state_ in function of the measurements.

Parameters:
  • contact_schedule – This indicates which end-effector is currently in contact.

  • joint_position – joint positions.

  • joint_velocity – joint velocities.

Private Members

BaseEkfWithImuKinSettings settings_
Eigen::VectorXd joint_position_

Joint positions reading.

Eigen::VectorXd joint_velocity_

Joint velocities reading.

Eigen::Vector3d imu_accelerometer_

Accelerometer reading.

Eigen::Vector3d imu_gyroscope_

Joint velocities.

SystemState predicted_state_

Predicted system state (next state).

SystemState posterior_state_

Posterior system state (current state).

pinocchio::Data pinocchio_data_

Rigid body dynamics data storage class.

std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> kin_ee_position_

Measured end-effectors positions expressed in the imu/base frame.

std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> kin_ee_velocity_

Measured end-effectors velocities expressed in the imu/base frame.

std::vector<pinocchio::FrameIndex> kin_ee_fid_

Pinocchio frame id corresponding to the end-effector potentially in contact.

Eigen::VectorXd q_kin_

Robot configuration with base at the center of the world.

Eigen::VectorXd dq_kin_

Robot velocity with static base frame.

Eigen::Matrix3d attitude_post_

Rotation matrix from the posterior state.

Eigen::Vector3d root_angular_velocity_

Imu/Base angular velocity.

Eigen::Vector3d root_angular_velocity_prev_

Imu/Base angular velocity previous value.

Eigen::Vector3d root_angular_acceleration_

Imu/Base angular acceleration.

Eigen::Vector3d root_linear_acceleration_

Imu/Base angular velocity.

Eigen::Vector3d gravity_

Gravity vector (default is negative along the z-axis).

Eigen::MatrixXd cont_proc_jac_

Continuous process jacobian.

Eigen::MatrixXd disc_proc_jac_

Discrete process jacobian.

Eigen::MatrixXd proc_noise_jac_

Process noise jacobian.

Eigen::MatrixXd cont_proc_noise_cov_

Continuous process noise covariance.

Eigen::MatrixXd disc_proc_noise_cov_

Discrete process noise covariance.

Eigen::MatrixXd disc_meas_noise_cov_

Discrete measurement noise covariance.

std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> kin_meas_root_velocity_

Linear velocity of the root (base/imu) measured from the kinematics.

Eigen::MatrixXd meas_jac_

Measurement jacobian.

Eigen::VectorXd meas_error_

Predicted base velocity, this is the predicted measurement.

Eigen::MatrixXd meas_covariance_

Measurement covariance.

Eigen::MatrixXd kalman_gain_

Kalman Gain computed during the update_step.

Eigen::LDLT<Eigen::MatrixXd> ldlt

LDLT decomposition to invert some matrix.

Eigen::VectorXd delta_state_

Update vector which is a delta state.

struct BaseEkfWithImuKinSettings

Subclassed by mim_estimation::RobotStateEstimatorSettings

Public Functions

inline virtual std::string to_string()

Public Members

bool is_imu_frame = true

Is the EKF estimating the imu or the base frame.

std::vector<std::string> end_effector_frame_names

Potential contact end effector frame names.

pinocchio::Model pinocchio_model

Rigid body dynamic model.

pinocchio::SE3 imu_in_base = pinocchio::SE3::Identity()

Imu position and orientation in the base frame.

double dt = 0.001

discretization time.

Eigen::Vector3d noise_accelerometer = 0.0001962 * 0.0001962 * (Eigen::Vector3d() << dt, dt, dt).finished()

Accelerometer noise covariance.

Eigen::Vector3d noise_gyroscope = 0.0000873 * 0.0000873 * (Eigen::Vector3d() << dt, dt, dt).finished()

Gyroscope noise covariance.

Eigen::Vector3d noise_bias_accelerometer = 0.0001 * 0.0001 * (Eigen::Vector3d() << 1.0, 1.0, 1.0).finished()

Accelerometer bias noise covariance.

Eigen::Vector3d noise_bias_gyroscope = 0.000309 * 0.000309 * (Eigen::Vector3d() << 1.0, 1.0, 1.0).finished()

Gyroscope bias noise covariance.

Eigen::Vector3d meas_noise_cov = (Eigen::Vector3d() << 1e-5, 1e-5, 1e-5).finished()

Continuous measurement noise covariance.

template<class classType, int _Order>
class ButterworthFilter

General filter template

template<typename _Scalar, int _Rows, int _Order>
class ButterworthFilter<Eigen::Matrix<_Scalar, _Rows, 1, Eigen::ColMajor, _Rows, 1>, _Order>

Specialization to an Eigen::Vector. This Filter class implements a butterworth low pass filter able to filter a vector of measurements. Only Eigen::Vectors or Eigen::Matrices with column dimension 1 are valid. Usage example: typedef Filter<Eigen::Matrix<double,6,1> > FilterType; INSTANTIATE FilterType myfilter; INITIALIZE myfilter.initialize(initial_state, filter_order, cuttoff_frequency); UPDATE myfilter.update(measurement); RETRIEVE EST myfilter.getData(estimate);

Public Types

typedef Eigen::Matrix<_Scalar, _Rows, 1, Eigen::ColMajor, _Rows, 1> VecToFilter

Input and Output type definition (VecToFilter)

Public Functions

ButterworthFilter()
~ButterworthFilter()
void initialize(const VecToFilter &current_state, double cutoff_frequency)

Function to initialize several parameters of the filter

Parameters:
  • current_state[in] initial state of the system of type VecToFilter

  • filter_order[in] order of the butterworth filter (integer >= 1)

  • cutoff_frequency[in] cuttoff frequency for the filter as percentage of the nyquist frequency. For example, if sampling frequency is 200Hz; then the Nyquist frequency is half of the sampling frequency, namely 100Hz. cut_off frequency is a double element of [0-1], such that 0 corresponds to 0*Nyquist frequency and 1 corresponds to a cutoff_frequency equal to the Nyquist frequency.

void update(const VecToFilter &new_measurement)

Function to update the filtered state based on the new raw measurement

Parameters:

new_measurement[in] new raw measurement of type VecToFilter

void getData(VecToFilter &current_state)

Function to ask for the filtered estimate

Parameters:

current_state[out] filtered estimate of state of type VecToFilter

void getData(Eigen::Ref<ButterworthFilter::VecToFilter> current_state)

Private Functions

bool compute_filter_coefficients()

Function to compute the coefficients of a Butterworth filter without reading them from a table. It only needs to be done once at initialization. return true if successfull computing filter coefficients

void CT_transform(const std::vector<std::complex<double>> &Czeros, const std::vector<std::complex<double>> &Cpoles, double Cgain, double omega, bool flag, std::vector<std::complex<double>> &CTzeros, std::vector<std::complex<double>> &CTpoles, double &CTgain)

Auxiliar function to compute the coefficients of a Butterworth filter.

void DT_transform(const std::vector<std::complex<double>> &CTzeros, const std::vector<std::complex<double>> &CTpoles, double CTgain, double T, std::vector<std::complex<double>> &DTzeros, std::vector<std::complex<double>> &DTpoles, double &DTgain)

Auxiliar function to compute the coefficients of a Butterworth filter.

void poly_coeffs(const std::vector<std::complex<double>> &roots, Eigen::Matrix<double, _Order + 1, 1> &coeffs)

Auxiliar function to compute the coefficients of a Butterworth filter.

Private Members

Eigen::Matrix<double, _Order + 1, 1> zeros_coeffs_vec_

storage of butterworth filter coefficients

Eigen::Matrix<double, _Order + 1, 1> poles_coeffs_vec_
bool initialized_filter_

logic variable

double cutoff_

order for the butterworth filter (Should be >=1)

cutoff frequency for the butterworth filter ([0-1] percentage of the nyquist frequency)

Eigen::Matrix<double, _Rows, _Order + 1> measurements_mat_

matrices to store past estimates and measurements for filtering

Eigen::Matrix<double, _Rows, _Order + 1> states_mat_
class DataCollector
#include <data_collector.hpp>

Subclassed by mim_estimation::io_tools::NonRtDataCollector

Public Functions

inline DataCollector()
inline virtual ~DataCollector()
virtual void addVariable(const double *data, const std::string &name, const std::string &units) = 0

virtual functions to add variables to data collection for different types

virtual void addVariable(const float *data, const std::string &name, const std::string &units) = 0
virtual void addVariable(const int *data, const std::string &name, const std::string &units) = 0
virtual void updateDataCollection() = 0

virtual function to update the collection with the recently added variables

virtual void stopDataCollection() = 0
virtual void startDataCollection() = 0
virtual bool isDataCollectionDone() = 0

virtual function to check whether data collection has completed:

void addVector(const Eigen::Ref<const Eigen::VectorXd> &data, const std::vector<std::string> &name, const std::vector<std::string> &units)

helper functions to unroll eigen vectors into simpler types that can be handled by the addVariable functions

arbitrary Eigen Vectors

void addVector(const Eigen::Ref<const Eigen::VectorXd> &data, const std::string &name, const std::vector<std::string> &extension, const std::vector<std::string> &units)

extension contains the list of strings to be appended to name for each elem of data

void addVector(const Eigen::Ref<const Eigen::VectorXd> &data, const std::string &name, const std::string &unit)

will just add 0,1,2..etc as extension to name

void addVector3d(const Eigen::Ref<const Eigen::Vector3d> &data, const std::string &name, const std::string &units)

the actual recorded names will be name_x, name_y, name_z

void addVector3d(const Eigen::Ref<const Eigen::Vector3d> &data, const std::string &name, const std::string &units, const std::string &extension)

the actual recorded names will be name_x, name_y, name_z plus extension

void addQuaternion(const Eigen::Ref<const Eigen::Vector4d> &data, const std::string &name)

the actual recorded names will be name_q0, name_q1, name_q2, name_q3 with units “-”

void addQuaternion(const Eigen::Quaterniond &data, const std::string &name)

the actual recorded names will be name_q0, name_q1, name_q2, name_q3 with units “-”

void addVector6d(const Eigen::Ref<const Eigen::Matrix<double, 6, 1>> &data, const std::string &name, const std::string &units)

the actual recorded names will have extension x,y,z,a,b,g

void addMatrix(const Eigen::Ref<const Eigen::MatrixXd> &data, const std::string &name, const std::string &unit)

arbitrary Eigen matrices (will just add matrix indes as extension to name, eg 11, 12, 21, 22

class DataReader
#include <data_reader.hpp>

Public Functions

inline DataReader()
inline ~DataReader()
void read(const std::string &fname)

read, reads a clmcplot file and fills the internal data structure.

Parameters:

fname – name of the d-file to read.

int getIndex(const std::string &stream_name)

findIndex, find the column index corresponding to the field name.

Parameters:

name – name of the field.

Returns:

the column index corresponding to the field name.

void getIndexes(const std::vector<std::string> &stream_names, std::vector<int> &indexes)

getIndexes:, find stream column indexes corresponding to the names.

Parameters:
  • names – list of the stream name.

  • indexes – the output list of indexes.

void fillPose(int row, const std::vector<int> &indexes, Eigen::Vector3d &pose, Eigen::Quaterniond &orientation)

fillPose, fill an existing pose object with the data.

Parameters:
  • row – row index homogenous to time/sampling_period.

  • indexes – the indexes of the data streams to copy in order: [x, y, z, qw, qx, qy, qz].

  • pose – the object to fill.

void fillVector(int row, const std::vector<int> &indexes, Eigen::Ref<Eigen::VectorXd> vec)

fillVector, fill an existing vector from the data

Parameters:
  • row – row index homogenous to time/sampling_period.

  • indexes – the indexes of the data streams to copy.

  • vec – the vector with the correct dimension that is filled

inline int getNbRows()

getNbRows, get the number of rows equivalent to the number of time step saved in the d-file

Returns:

the number of time step saved

inline double getValue(int row, int index)

getValue, get the value of a specific stream at a specific time

Parameters:
  • row – row index homogenous to time/sampling_period.

  • index – the index of the data streams to copy from.

Returns:

the value

inline double getFrequency()

getFrequence, get the getFrequence of the read data

Returns:

the frequence

Private Members

Eigen::MatrixXd data_
std::vector<std::string> var_names_
std::vector<std::string> units_
int nb_rows_
int nb_cols_
int buffer_size_
double frequency_
template<class S, class M>
class EKF
#include <ekf.hpp>

This class implements an extended Kalman Filter (EKF).

This class implements a templated Extended Kalman Filter that receives a State class “S” and a measurement class “M”. Both templated class must have this following operator: -, +, =, <<. This operator must be eigen compatible. To achieve this in a compact way I strongly suggest inheriting directly from the class Eigen::Vector<N> (see Eigen documentation https://eigen.tuxfamily.org/dox/TopicCustomizing_InheritingMatrix.html).

The main sources of reading comes from

  • [1] “S. Thrun, W. Burgard, and D. Fox, Probabilistic Robotics, 2000” (Chapter 3)

  • [2] “http://wolfweb.unr.edu/~fadali/EE782/NumEvalQphi.pdf”

  • [3] “https://en.wikipedia.org/wiki/Extended_Kalman_filter”

The notation used in this documentation is the one from “http://wolfweb.unr.edu/~fadali/EE782/NumEvalQphi.pdf”.

\[\begin{split}\begin{align} x_t = g(u_t, x_{t-1}) + \epsilon_t \\ z_t = h(x_t) + \delta_t \end{align}\end{split}\]
With \( x_t \) the system state, \( u_t \) the system control, \( g \) the process evolution, \( \epsilon_t \approx N(0, R_t) \) the process Gaussian noise, \( h \) the measurement evolution and \( \delta_t \approx N(0, Q_t) \) the measurement Gaussian noise. The first equation depicts the “process” in the code. The second equation represents the “measurement” in the code.

Using a taylor expansion of the previous equation we get:

\[\begin{split}\begin{align} x_t = g(u_t, \mu_{t-1}) + G_t \; * \; (x_{t-1} - \mu_{t-1}) + \epsilon_t \\ z_t = h(\mu_t) + H_t \; * \; (x_{t} - \mu_{t}) + \delta_t \end{align}\end{split}\]
With \( \mu_{t} \) the average of the estimated state of covariance \( \Sigma_t \). The equation of the EKF routine are defined with the “update_filter” function.

The mapping between the variable names and this piece of documentation is done next to each variable.

Public Functions

EKF(bool numerical_jac, bool is_discrete, double dt, unsigned lin_order = 2)

EKF, constructor of the class.

Parameters:
  • numerical_jac – do we compute the Jacobians analytically or not?

  • is_discrete – is the process discrete?

  • dt – the sampling period of the EKF.

inline ~EKF()

Default destructor.

void updateFilter(bool update_on)

updateFilter: compute a pass of the extended Kalman filter

From here on we only have access to \( \mu_{t-1} \) and \( \Sigma_{t-1} \) the previous estimated state along time. First of all we need to check if the system is a discrete one (see constructor). If the system is continuous we need to build a discrete approximation of it. In order to do so we use the Van Loan’s method (see [2] slide 15).

  • 1/ Compute the dynamic matrix of the continuous process \( M \)

    \[\begin{align} M = \left[ \left. \frac{-G_t}{0} \right| \frac{E_t R_t E_t^T}{G_t^T} \right] \end{align}\]
    With \( E_t \) being the jacobian of the noise. In [2], \( E_t \) is also considered as the control jacobian in a way.

  • 2/ Obtain the matrix M exponential

    \[\begin{align} e^{M \Delta t} = \left[ \left. \frac{ e^{-G_t \Delta t} }{0} \right| \frac{ e^{-G_t \Delta t} F_{t, disc} }{ e^{G_t^T \Delta t} } \right] \end{align}\]

  • 3/ Transpose the lower right corner to compute the discretized process noise covariance.

    \[\begin{align} R_{t, disc} = e^{G_t \Delta t} = (e^{G_t^T \Delta t})^T \end{align}\]

  • 4/ Compute the discretized process jacobian as follow:

    \[\begin{align} F_{t, disc} = R_{t, disc} \;\;\; e^{M \Delta t}[\text{upper right corner}] \end{align}\]
    In the following we will discard the \( {disc} \) subscript in the expression of the process Jacobian and noise covariance for sake of clarity. We assume that the system is either discrete or already discretized.

When the system has been discretized (or is discrete) we compute the EKF with the following procedure. First we need to predict what is supposed to be the current estimated state \( \tilde{\mu}_{t} \) and its Covariance \( \tilde{\Sigma}_{t} \) according to the model and the current control:

\[\begin{split}\begin{align} \tilde{\mu}_{t} &= g(u_t, \mu_{t-1}) \\ \tilde{\Sigma}_{t} &= G_t \Sigma_{t-1} G_t^T + R_t \end{align}\end{split}\]
The second step consist in introducing the actual measurement when one occur.
\[\begin{split}\begin{align} K_{t} &= \tilde{\Sigma}_{t} H_t^T (H_t \tilde{\Sigma}_t H_t^T + Q_t)^{-1} \\ \mu_{t} &= \tilde{\mu}_{t} + K_t (z_t - h(\tilde{\mu}_t)) \\ \Sigma_{t} &= (I - K_t H_t) \tilde{\Sigma}_{t} \end{align}\end{split}\]

Parameters:

update_on – is the measurement new?

virtual Eigen::Matrix<double, N, 1> getFilterState(void) = 0

getFilterState

Returns:

the current state estimate \( \mu_{t} \)

void printDebug(void)

printDebug, print all the protected method of the class for debugging purposes

Public Static Attributes

static const int N = S::state_dim

State dimension

static const int P = S::noise_dim

Noise dimension

static const int K = M::meas_dim

Measurement dimension

Protected Functions

virtual Eigen::Matrix<double, N, 1> processModel(S &s) = 0

processModel, a model of the continuous/discrete state dynamics \( g(u_t, x_{t-1}) \)

Parameters:

s\( [x_{t-1}^T \;\; u_t^T]^T \)

Returns:

the predicted state (Max: should not return anything and update state_pre_?)

virtual void formProcessJacobian(void) = 0

formProcessJacobian, compute the Jacobian of the process \( G_t \)

virtual void formProcessNoise(void) = 0

formProcessNoise, compute the covariance of the process noise \( R_t \)

virtual void formNoiseJacobian(void) = 0

formNoiseJacobian, compute the Jacobian of the process noise \( E_t \)

virtual Eigen::Matrix<double, K, 1> measModel(S &s) = 0

measModel, a model of the measurement dynamics \( h(x_t) \)

Parameters:

s – a state \( x_t \)

Returns:

the predicted measurement (Max: should not return anything and update meas_pred_?)

virtual void formMeasJacobian(void) = 0

formMeasJacobian, compute the Jacobian of the measurement \( H_t \)

virtual void formMeasNoise(void) = 0

formMeasJacobian, compute the measure covariance \( Q_t \)

virtual void formActualMeas(void) = 0

formMeasJacobian, compute the measurement from sensors \( z_t \)

void computeJacobians(Eigen::MatrixXd &G_t, Eigen::MatrixXd &H_t, double ds)

computeJacobians, compute the finite differentiation

Parameters:
  • G_t[inout] the process jacobian to compute

  • H_t[inout] the measurement jacobian

  • ds[inout] the finite differentiation delta \( \frac{f(x+ds) - f(x-ds)}{2ds} \)

bool check_jacobians(bool evaluate)

check_the_jacobians, this function computes the jacobian from the discrete model and from the continuous jacobian discretized and compare them

Parameters:

evaluate[in] true, the function is computing the check/false it does nothing

Returns:

a boolean that says if everything is alright. for Van Loan discretization, \( M \)

Protected Attributes

S state_pre_

Predicted state ( \( \tilde{\mu} \), \( \tilde{\Sigma} \))

S state_post_

State of the filter. One variable is used for the previous ( \( \mu_{t-1} \), \( \Sigma_{t-1} \)) and current state ( \( \mu_{t} \), \( \Sigma_{t} \))

M meas_actual_

Current measurement ( \( z_{t} \))

M meas_pred_

Predicted measurement ( \( h(\tilde{\mu}_t)\) )

Eigen::MatrixXd VL_mat_

for Van Loan discretization, \( e^{M dt} \)

Eigen::MatrixXd exp_VL_mat_

discretized/discrete process Jacobian, \( G_{t,disc}/G_t \)

Eigen::MatrixXd proc_jac_disc_

user input process Jacobian, \( G_t \)

Eigen::MatrixXd proc_jac_

Jacobian of the process noise, \( E_t \)

Eigen::MatrixXd noise_jac_

Jacobian of the measurement, \( H_t \)

Eigen::MatrixXd meas_jac_

user input covariance of the process noise \( R_t \)

Eigen::MatrixXd proc_noise_

discretized/discrete covariance of the process noise \( R_{t,disc}/R_t \)

Eigen::MatrixXd proc_noise_disc_

user input covariance of the measure noise \( Q_t \)

Eigen::MatrixXd meas_noise_

covariance of the process noise \( Q_t \) assuming a discrete measurement

Eigen::MatrixXd meas_noise_disc_

Kalman filter gain matrix \( K_t \)

Eigen::MatrixXd gain_mat_

LDLT decomposition to invert some matrix

Eigen::LDLT<Eigen::MatrixXd> ldlt

Do we compute the Jacobian numerically or analytically?

bool numerical_jac_

Is the process discrete?

bool is_discrete_

sampling period

double dt_

order of the process dynamic linearization

unsigned lin_order_
class EndEffectorForceEstimator

Public Types

typedef std::map<std::string, pinocchio::FrameIndex> EndEffectorIdMap
typedef std::map<pinocchio::FrameIndex, MatrixX3, std::less<pinocchio::FrameIndex>, Eigen::aligned_allocator<std::pair<const pinocchio::FrameIndex, MatrixX3>>> MatrixX3Map
typedef std::map<pinocchio::FrameIndex, pinocchio::Data::Matrix6x, std::less<pinocchio::FrameIndex>, Eigen::aligned_allocator<std::pair<const pinocchio::FrameIndex, pinocchio::Data::Matrix6x>>> Matrix6xMap
typedef std::map<pinocchio::FrameIndex, Eigen::Matrix<double, 6, 1>, std::less<pinocchio::FrameIndex>, Eigen::aligned_allocator<std::pair<const pinocchio::FrameIndex, Eigen::Matrix<double, 6, 1>>>> EndEffectorForceMap

Public Functions

EndEffectorForceEstimator()

Construct a new EndEffectorForceEstimator object.

No memory allocation,

See also

initialize. Use the default constructor for eigen and pinocchio objects.

~EndEffectorForceEstimator()

Destroy the EndEffectorForceEstimator object.

void initialize(const std::string &urdf_path, const std::vector<std::string> &frame_name = std::vector<std::string>())
void add_contact_frame(const std::string &frame_name)
void add_contact_frame(const std::vector<std::string> &frame_names)
void run(const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_torques)
const Eigen::Matrix<double, 6, 1> &get_force(const std::string &frame_name)
inline std::string to_string()

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, Eigen::Dynamic, 3 > MatrixX3

Private Members

Matrix6xMap contact_jacobians_

Contact Jacobians associated to a robot frame.

MatrixX3Map contact_jacobians_transpose_

Transpose of the contact Jacobians associated to a robot frame.

EndEffectorForceMap end_effector_forces_

Forces applied by the environment at the end-effector [N].

EndEffectorIdMap end_effector_id_map_

Map from model frame name to frame id.

pinocchio::Model robot_model_

Rigid body model of the robot, constructed from a urdf file.

pinocchio::Data robot_data_

Cache of the algorithm performed on the robot model.

Eigen::VectorXd q_

Internal robot configuration to perform the rigid body algorithms.

Eigen::ColPivHouseholderQR<MatrixX3> solver_

Linear solver for the equation $f A x = B $f.

int nb_joint_

Number of joint Dof.

class EstimatorTests : public Test

The EstimatorTests class: test suit template for seting up the unit tests for the IMU Vicon base state estimator.

In SetUp, for test, we create all the configuration file paths In TearDown, we do nothing

Protected Functions

inline void SetUp()
inline void TearDown()

Protected Attributes

std::string yaml_file_
std::string d_file_
class EstimatorViconImuTest

Public Functions

inline EstimatorViconImuTest(std::string yaml_file, std::string d_file)

This class tests the mim_estimation based on IMU and Vicon measurement.

inline void run()

run, simple method that execute the estimation of the base position from motion capture and IMU data saved from SL

inline void dump(std::string file_name)
inline void get_data_from_file(const int row, Eigen::Vector3d &gyroscope, Eigen::Vector3d &accelerometer, Eigen::Matrix4d &vicon_base_pose, Eigen::Quaterniond &input_vicon_base_quat, bool &vicon_is_new_frame)

get_data_from_file

Parameters:
  • row – row index homogenous to time/sampling_period.

  • gyroscope – output imu data copied from the data set

  • accelerometer – output imu data copied from the data set

  • unfiltered_joint_data – joint position copied from the data set

  • filtered_joint_data – filtered joint position copied from the data set

  • vicon_base_pose – position of the based measured form the Vicon system copied from the data set

  • vicon_is_new_frame – True is the Vicon data if actually a new one.

inline void subscribe_to_data_collector()

subscribe_to_data_collector, collect the address of all variables to save

inline void get_data_indexes()

get_data_indexes In order to parse the SL data file one need the indexes associated to the data.

This method computes the different names and indexes.

inline void display_one_statistics(double avg, double min, double max, std::string name)
inline void display_all_statistics()
inline void compute_all_statistics()
inline void compute_one_statistics(Eigen::Ref<Eigen::MatrixXd> mat, double &avg, double &min, double &max)

Public Members

double avg_err_base_pose
double avg_err_base_pose_x
double avg_err_base_pose_y
double avg_err_base_pose_z
double max_err_base_pose
double max_err_base_pose_x
double max_err_base_pose_y
double max_err_base_pose_z
double min_err_base_pose
double min_err_base_pose_x
double min_err_base_pose_y
double min_err_base_pose_z
double avg_err_base_quat_x
double avg_err_base_quat_y
double avg_err_base_quat_z
double max_err_base_quat_x
double max_err_base_quat_y
double max_err_base_quat_z
double min_err_base_quat_x
double min_err_base_quat_y
double min_err_base_quat_z

Private Members

YAML::Node config_
YAML::Node config_est_
double update_frequency_
io_tools::DataReader data_reader_
io_tools::NonRtDataCollector data_collector_
double time_
std::vector<int> gyroscope_ids_
std::vector<int> accelerometer_ids_
std::vector<int> vicon_base_pose_ids_
int vicon_is_new_frame_id_
Eigen::Vector3d input_gyroscope_
Eigen::Vector3d input_accelerometer_
Eigen::Matrix4d input_vicon_base_pose_
Eigen::Quaterniond input_vicon_base_quat_
bool input_vicon_is_new_frame_
Eigen::Vector3d output_imu_position_
Eigen::Quaterniond output_imu_orientation_
Eigen::Vector3d output_imu_linear_velocity_
Eigen::Vector3d output_imu_angular_velocty_
Eigen::Vector3d output_accel_bias_
Eigen::Vector3d output_gyro_bias_
Eigen::Vector3d output_base_position_
Eigen::Quaterniond output_base_orientation_
Eigen::Vector3d output_base_linear_velocity_
Eigen::Vector3d output_base_angular_velocity_
Eigen::MatrixXd error_base_pose_
Eigen::MatrixXd error_base_quat_
std::unique_ptr<mim_estimation::EkfViconImu> vicon_bse_
class NonRtDataCollector : public mim_estimation::io_tools::DataCollector

Public Functions

inline NonRtDataCollector()
inline virtual ~NonRtDataCollector()
virtual void addVariable(const double *data, const std::string &name, const std::string &units)

virtual functions to add variables to data collection for different types

virtual void addVariable(const float *data, const std::string &name, const std::string &units)
virtual void addVariable(const int *data, const std::string &name, const std::string &units)
virtual void addVariable(const bool *data, const std::string &name, const std::string &units)
virtual void updateDataCollection()

virtual function to update the collection with the recently added variables

virtual void stopDataCollection()
virtual void startDataCollection()
virtual bool isDataCollectionDone()

virtual function to check whether data collection has completed:

float reverseFloat(const float inFloat)

convertion big endian and little endian

void dump(std::string path)

dump the data in SL format the

Private Members

std::deque<std::deque<double>> double_data_
std::deque<std::string> double_names_
std::deque<std::string> double_units_
std::deque<const double*> double_ptr_
std::deque<std::deque<float>> float_data_
std::deque<std::string> float_names_
std::deque<std::string> float_units_
std::deque<const float*> float_ptr_
std::deque<std::deque<int>> int_data_
std::deque<std::string> int_names_
std::deque<std::string> int_units_
std::deque<const int*> int_ptr_
std::deque<std::deque<bool>> bool_data_
std::deque<std::string> bool_names_
std::deque<std::string> bool_units_
std::deque<const bool*> bool_ptr_
bool running_
struct RobotStateEstimation

Public Types

typedef Eigen::Matrix<double, 6, 1> EigenVector6d
typedef mim_estimation::RobotPosture::EigenVectorNDofsd EigenVectorNDofsd
typedef standard_filters::ButterworthFilter<EigenVectorNDofsd, 2> JointDOFFilter
typedef standard_filters::ButterworthFilter<EigenVector6d, 2> WrenchFilter
typedef std::array<mim_estimation::ContactDescritpion, Robot::n_endeffs_> ContactDescriptionArray
typedef std::unique_ptr<mim_estimation::JointPositionSensors> JointPositionSensorPtr
typedef std::unique_ptr<mim_estimation::BaseStateSensor> BaseStateSensorPtr
typedef std::unique_ptr<mim_estimation::IMU> IMUPtr
typedef std::unique_ptr<mim_estimation::FTSensor> FTSensorPtr
typedef std::array<FTSensorPtr, Robot::n_endeffs_> FTSensorPtrArray
typedef std::unique_ptr<mim_estimation::Kinematics> KinematicsPtr
typedef std::shared_ptr<VisualizationToolsInterface> VisToolsPtr

Public Functions

RobotStateEstimation(YAML::Node n, std::unique_ptr<mim_estimation::RobotProperties> robot_prop, JointPositionSensorPtr joint_sensors, BaseStateSensorPtr base_state_sensor, FTSensorPtrArray wrench_sensors, IMUPtr imu_sensors, KinematicsPtr filtered_kinematics, KinematicsPtr unfiltered_kinematics, VisToolsPtr vis_tools_interface)
RobotStateEstimation(const RobotStateEstimation&) = delete
RobotStateEstimation(RobotStateEstimation&&) = delete
inline virtual ~RobotStateEstimation()
void initialize(const mim_estimation::ContactDescritpion (&contact_description)[Robot::n_endeffs_])
void update()
void computeFootCoPsOnFloor()
inline Eigen::Vector3d getFootContactPointProjected(int endeff_id)
inline bool isSimulated(void)
void subscribe_to_data_collector(data_collection::DataCollector &data_collector, std::string name)

Public Members

std::unique_ptr<mim_estimation::RobotProperties> robot_prop_
JointPositionSensorPtr unfiltered_joint_position_sensor_
BaseStateSensorPtr simulated_base_state_
KinematicsPtr unfiltered_forward_kinematics_
IMUPtr unfiltered_imu_
FTSensorPtrArray unfiltered_wrench_sensors_
int joint_sensors_filter_cutoff_
int wrench_filter_cutoff_
JointDOFFilter position_filter_
JointDOFFilter velocity_filter_
std::array<WrenchFilter, Robot::n_endeffs_> wrench_filters_
BaseEstEKF base_state_estimator_
std::shared_ptr<VisualizationToolsInterface> vis_tools_interface_
double force_threshold_for_contact_
mim_estimation::RobotPosture filtered_posture_
mim_estimation::RobotVelocity filtered_velocity_
std::array<mim_estimation::FTSensorData, Robot::n_endeffs_> filtered_wrench_
std::array<mim_estimation::FTSensorData, Robot::n_endeffs_> endeff_wrench_
std::vector<Eigen::Vector3d> filt_foot_cops_
std::vector<Eigen::Vector3d> filt_foot_cops_rgb_
std::vector<Eigen::Vector3d> filt_contact_points_
Eigen::Vector3d filt_overall_cop_
Eigen::Matrix4d floor_tf_
mim_estimation::ContactDescritpion contacts_[Robot::n_endeffs_]
KinematicsPtr filtered_kinematics_
bool use_vicon_base_

Private Functions

void update_base_estimation_ekf()
void update_vicon_base_state_ekf()
virtual bool update_opengl(const mim_estimation::RobotPosture &posture) = 0
class RobotStateEstimator

This class has for purpose to estimate the state of the robot in the current environment.

It really on different classes implemented in this package and provide a uniforme way to interact with them.

For example there is an end-effector force estimation class that can be used for contact detection needed by an EKF. This class creates this pipeline in a transparent way for the user. The user simply need to pick which scientific method are to be used among the available ones.

Public Types

typedef std::map<std::string, Eigen::Vector3d, std::less<std::string>, Eigen::aligned_allocator<std::pair<const std::string, Eigen::Vector3d>>> ForceInWorldMap

Public Functions

RobotStateEstimator()

Construct a new Base State Estimator object.

~RobotStateEstimator()

Destroy by default the Base State Estimator object.

void initialize(const RobotStateEstimatorSettings &settings)
void set_initial_state(Eigen::Ref<const Eigen::VectorXd> initial_robot_configuration, Eigen::Ref<const Eigen::VectorXd> initial_robot_velocity)
void run(const std::vector<bool> &contact_schedule, Eigen::Ref<const Eigen::Vector3d> imu_accelerometer, Eigen::Ref<const Eigen::Vector3d> imu_gyroscope, Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity)

Estimate the robot base velocity and postion assuming the contact schedule is known.

Parameters:
  • contact_schedule

  • imu_accelerometer

  • imu_gyroscope

  • joint_position

  • joint_velocity

  • joint_torque

void run(Eigen::Ref<const Eigen::Vector3d> imu_accelerometer, Eigen::Ref<const Eigen::Vector3d> imu_gyroscope, Eigen::Ref<const Eigen::VectorXd> joint_position, Eigen::Ref<const Eigen::VectorXd> joint_velocity, Eigen::Ref<const Eigen::VectorXd> joint_torque)

Estimate the robot base velocity and postion and the contact states.

Parameters:
  • imu_accelerometer

  • imu_gyroscope

  • joint_position

  • joint_velocity

  • joint_torque

void get_state(Eigen::Ref<Eigen::VectorXd> robot_configuration, Eigen::Ref<Eigen::VectorXd> robot_velocity)
const Eigen::VectorXd &get_robot_configuration() const
const Eigen::VectorXd &get_robot_velocity() const
const std::vector<bool> &get_detected_contact() const
const Eigen::Vector3d &get_force(const std::string &frame_name)
void set_settings(const RobotStateEstimatorSettings &settings)
const RobotStateEstimatorSettings &get_settings() const

Private Members

EndEffectorForceEstimator ee_force_estimator_

End-effector force estimator.

Estimate the forces in the base frame.

BaseEkfWithImuKin base_ekf_with_imu_kin_

EKF that estimating the localization of the base relative to it’s initial position.

RobotStateEstimatorSettings settings_

Settings of this class.

std::vector<bool> detected_contact_

Contact detection from force.

Eigen::VectorXd current_robot_configuration_

Current robot configuration.

Eigen::VectorXd current_robot_velocity_

Current robot velocity.

Eigen::Quaterniond rot_base_in_world_

Current base orientation in the estimated world frame.

ForceInWorldMap force_in_world_map_

Force in world frame.

class RobotStateEstimator : public Entity

This class define a dynamic graph wrapper around the vicon client.

Public Functions

DYNAMIC_GRAPH_ENTITY_DECL()
RobotStateEstimator(const std::string &name)

Construct a new Vicon Client Entity object.

Parameters:

name – Entity name.

~RobotStateEstimator()

Destroy the Vicon Client Entity object.

void initialize(const RobotStateEstimatorSettings &settings)

Connect to the vicon system and start a.

Parameters:

host_name

void set_initial_state(Eigen::Ref<const Eigen::VectorXd> initial_robot_configuration, Eigen::Ref<const Eigen::VectorXd> initial_robot_velocity)

Add a signal that contains the pose of the desired object.

Private Functions

int &signal_callback_one_iteration(int&, const int &time)

Signal callback for the one_iteration_sout_ signal.

dynamicgraph::Vector &signal_callback_robot_configuration(dynamicgraph::Vector &res, const int &time)

Signal callback for the robot_configuration_sout_ signal.

dynamicgraph::Vector &signal_callback_robot_velocity(dynamicgraph::Vector &res, const int &time)

Signal callback for the robot_velocity_sout_ signal.

dynamicgraph::Vector &signal_callback_base_posture(dynamicgraph::Vector &res, const int &time)

Signal callback for the base_posture_sout_ signal.

dynamicgraph::Vector &signal_callback_base_velocity_body(dynamicgraph::Vector &res, const int &time)

Signal callback for the base_velocity_body_sout_ signal.

dynamicgraph::Vector &signal_callback_detected_contact(dynamicgraph::Vector &res, const int &time)

Signal callback for the detected_contact_sout_ signal.

dynamicgraph::Vector &signal_callback_force(const std::string &frame_name, dynamicgraph::Vector &res, const int &time)

Signal callback for the robot_velocity_sout_ signal.

Private Members

SignalIn imu_accelerometer_sin_

Sensor reading input signal: imu accelerometer.

SignalIn imu_gyroscope_sin_

Sensor reading input signal: imu gyroscope.

SignalIn joint_position_sin_

Sensor reading input signal: joint position.

SignalIn joint_velocity_sin_

Sensor reading input signal: joint velocity.

SignalIn joint_torque_sin_

Sensor reading input signal: joint torque.

SignalTrigger one_iteration_sout_

Create an output signal which computes the estimation.

All other signal depend one this one. This allow the computation to be ran only once per graph evaluation. And to compute the estimation early on to allow convergence of the algorithm during initialization.

SignalOut robot_configuration_sout_

Output signal carrying the robot configuration in generalized coordinates.

SignalOut robot_velocity_sout_

Output signal carrying the robot velocity in generalized coordinates.

SignalOut base_posture_sout_

Output signal carrying the robot base SE3 position.

SignalOut base_velocity_body_sout_

Output signal carrying the robot base SE3 velocity.

SignalOut detected_contact_sout_

Output signal carrying the list of detected contact using doubles.

std::deque<std::unique_ptr<SignalOut>> force_sout_

Signals for the end-effector external force expressed in the world frame.

mim_estimation::RobotStateEstimator estimator_

State estimator wrapped by this entity.

struct RobotStateEstimatorSettings : public mim_estimation::BaseEkfWithImuKinSettings

Public Functions

inline virtual std::string to_string()

Convert the current object in human readable string.

Public Members

std::string urdf_path

Path to th robot URDF file.

double force_threshold_up = 10

Threshold on the rising force norm.

double force_threshold_down = 5

Threshold on the decreasing force norm.

class SimpleEKF : public mim_estimation::standard_filters::EKF<SimpleEKFState, SimpleEKFMeasure>
#include <simple_1d_ekf.hpp>

Public Functions

inline SimpleEKF(double init_pos, double dt, bool is_discrete)
inline ~SimpleEKF()
inline void update(Eigen::Matrix<double, 1, 1> pos, bool new_measured_value)
inline Eigen::Matrix<double, N, 1> get_filter_state(void)
inline void subscribe_to_data_collector(mim_estimation::io_tools::DataCollector &data_collector)

Private Functions

inline Eigen::Matrix<double, N, 1> process_model(SimpleEKFState &s)

process_model

  • \[\begin{align} \dot{pos} = (meas_vel - meas_vel_bias) \dot{bias} = 0.0 \end{align}\]

Parameters:

s – current state

Returns:

out: the predicted state

inline void form_process_jacobian(void)

form_process_jacobian

inline void form_process_noise(void)
inline void form_noise_jacobian(void)
inline Eigen::Matrix<double, K, 1> measurement_model(SimpleEKFState &s)

measurement_model

Parameters:

s – current state

Returns:

out: the predicted measurement

inline void form_measurement_jacobian(void)
inline void form_measurement_noise(void)
inline void form_actual_measurement(void)

Private Members

Eigen::Matrix<double, 1, 1> vel_
Eigen::Matrix<double, 1, 1> meas_pos_
Eigen::Matrix<double, 1, 1> meas_vel_
double q_proc_noise_
double q_meas_noise_
double init_var_
class SimpleEKFMeasure : public Eigen::Matrix<double, 1, 1>
#include <simple_1d_ekf.hpp>

Public Functions

inline SimpleEKFMeasure(void)
template<typename OtherDerived>
inline SimpleEKFMeasure(const Eigen::MatrixBase<OtherDerived> &other)
template<typename OtherDerived>
inline SimpleEKFMeasure &operator=(const Eigen::MatrixBase<OtherDerived> &other)

Public Members

Eigen::Ref<Eigen::Matrix<double, 1, 1>> meas_pos_
Eigen::Matrix<double, 1, 1> meas_cov

Public Static Attributes

static const int meas_dim = 1
class SimpleEKFState : public Eigen::Matrix<double, 1, 1>
#include <simple_1d_ekf.hpp>

Public Functions

inline SimpleEKFState(void)
template<typename OtherDerived>
inline SimpleEKFState(const Eigen::MatrixBase<OtherDerived> &other)
template<typename OtherDerived>
inline SimpleEKFState &operator=(const Eigen::MatrixBase<OtherDerived> &other)
inline Eigen::Matrix<double, 1, 1> getState()

Public Members

Eigen::Ref<Eigen::Matrix<double, 1, 1>> pos_
Eigen::Matrix<double, 1, 1> state_cov

Public Static Attributes

static const int state_dim = 1
static const int noise_dim = 1
struct SystemState

System state data.

Public Members

Eigen::Vector3d position = Eigen::Vector3d::Zero()

Base/Imu position.

Eigen::Vector3d linear_velocity = Eigen::Vector3d::Zero()

Base/Imu linear velocity.

Eigen::Quaterniond attitude = Eigen::Quaterniond::Identity()

Base/Imu linear attitude.

Eigen::Vector3d bias_accelerometer = Eigen::Vector3d::Zero()

Accelerometer bias.

Eigen::Vector3d bias_gyroscope = Eigen::Vector3d::Zero()

Gyroscope bias.

Eigen::MatrixXd covariance = Eigen::MatrixXd::Zero(state_dim, state_dim)

Process covariance.

Public Static Attributes

static const int state_dim = 15

State dimension.

static const int noise_dim = 12

Process noise dimension.

class TestEKF : public Test

Protected Functions

inline virtual void SetUp()
inline virtual void TearDown()
template<class S, class M>
class UKF
#include <ukf.hpp>

Public Functions

UKF(bool numerical_jac, bool is_discrete, bool update_on, double dt)
inline ~UKF()
virtual void initialize(void) = 0
inline virtual void updateControls(void)
void update(void)
virtual Eigen::Matrix<double, N, 1> get_filter_state(void) = 0
void print_debug(void)

Public Static Attributes

static const int N = S::state_dim
static const int P = S::noise_dim
static const int K = M::meas_dim
static const int L = 2 * N + 1

Protected Functions

virtual Eigen::Matrix<double, N, 1> process_model(S &s) = 0
virtual Eigen::Matrix<double, K, 1> measurement_model(S &s) = 0
virtual void form_process_jacobian(void) = 0
virtual void form_process_noise(void) = 0
virtual void form_noise_jacobian(void) = 0
virtual void form_measurement_noise(void) = 0
virtual void form_actual_measurement(void) = 0

Protected Attributes

S state_pre_
S state_post_
M meas_actual_
M meas_pred_
Eigen::MatrixXd proc_jac_
Eigen::MatrixXd proc_jac_disc_
Eigen::MatrixXd noise_jac_
Eigen::MatrixXd proc_noise_
Eigen::MatrixXd proc_noise_disc_
Eigen::MatrixXd meas_jac_
Eigen::MatrixXd meas_noise_
Eigen::MatrixXd meas_noise_disc_
Eigen::MatrixXd state_weights_
Eigen::MatrixXd cov_weights_
Eigen::MatrixXd spoints_mat_
Eigen::MatrixXd spoints_proc_
Eigen::MatrixXd spoints_meas_
Eigen::MatrixXd cross_cov_
Eigen::MatrixXd gain_mat_
Eigen::LDLT<Eigen::MatrixXd> ldlt
double alpha_
double beta_
double kappa_
double lambda_
bool numerical_jac_
bool is_discrete_
bool update_on_
double dt_
namespace boost

Functions

template<typename T>
T *get_pointer(std::shared_ptr<T> p)
namespace python
namespace estimation
namespace example_tasks
namespace mim_estimation

Functions

template<class Vector>
inline boost::python::list std_vector_to_py_list(const Vector &vector)
boost::python::list get_measurement(BaseEkfWithImuKin *obj)
void bind_base_ekf_with_imu_kin()
void bind_end_effector_force_estimator()
void bind_robot_state_estimator()
BOOST_PYTHON_MODULE(mim_estimation_cpp)
void bind_robot_state_estimator_settings()
namespace dynamic_graph

Typedefs

typedef dynamicgraph::SignalTimeDependent<int, int> SignalTrigger

Simple shortcut for code writing convenience.

typedef dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> SignalOut

Simple shortcut for code writing convenience.

typedef dynamicgraph::SignalPtr<dynamicgraph::Vector, int> SignalIn

Simple shortcut for code writing convenience.

Functions

DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN (RobotStateEstimator, "RobotStateEstimator")
std::string make_signal_string(const bool &is_input_signal, const std::string &class_name, const std::string &object_name, const std::string &signal_type, const std::string &signal_name)
namespace io_tools
namespace standard_filters
namespace test
file demo_ekf_vicon_imu.cpp
#include “mim_estimation/demos_and_tests/ekf_vicon_imu_simple.hpp”

Simple demo that runs the EkfViconImu filter using a d-file as data.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

Functions

int main(int argc, char **argv)

main, simple main that execute the estimation of the base position from motion capture and IMU data saved from SL

Parameters:
  • argc – must be equal to 2

  • argv – contains the path to the data-file

Returns:

0 by default

file ekf.hpp
#include <iostream>
#include “Eigen/Eigen”
#include “mim_estimation/standard_filters/ekf.hxx”

Implementation of the Extended Kalman Filter (EKF).

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file ekf.hxx
#include <fstream>
#include “mim_estimation/standard_filters/ekf.hpp”

Implements the EKF templated class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file ekf_vicon_imu_simple.hpp
#include <fstream>
#include <string>
#include “mim_estimation/ekf_vicon_imu.hpp”

Implements a testing class for the Vicon and IMU based estimator. It loads a yaml configuration file and a SL data file, estimate the state from these data and compare to the vicon trajectory.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file robot_state_estimation.cpp
#include <estimator/robot_state_estimation.h>
#include <example_tasks/utils/robot_part_iterators.h>

Remark

Author

Alexander Herzog

Date

Oct 26, 2015

file robot_state_estimation.hpp
#include <array>
#include <memory>
#include <data_collection/data_collector.h>
#include <mim_estimation/contact_helper.h>
#include <mim_estimation/kinematics.h>
#include <mim_estimation/robot_properties.h>
#include <mim_estimation/robot_state_representation.h>
#include <mim_estimation/sensors.h>
#include <robot_properties/robot.h>
#include <standard_filters/butterworth_filter.h>
#include <yaml-cpp/yaml.h>
#include “geometry_utils/Transformations.h”
#include “hinvdyn_balance/ankle_ft_sensor.h”
#include “base_state_estimators/BaseEstEKF.h”
#include “visualization_tools/VisualizationToolsInterface.h”
file simple_1d_ekf.hpp
#include <Eigen/Core>
#include “mim_estimation/standard_filters/ekf.hpp”
file test_ekf_vicon_imu.cpp
#include <gtest/gtest.h>
#include “mim_estimation/demos_and_tests/ekf_vicon_imu_simple.hpp”

License:

BSD 3-clause

Unit tests for the estimator based on Nick Rotella’s PhD.
Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

Functions

TEST_F(EstimatorTests, test_estimator_vicon_imu_test)
file test_extended_kalman_filter.cpp
#include <gtest/gtest.h>
#include <stdlib.h>
#include <random>
#include “simple_1d_ekf.hpp

Functions

double generate_1d_noisy_sinus(std::default_random_engine noise_gen, std::normal_distribution<double> noise, double amplitude, double pulsation, double time)

generate_1d_noisy_sinus: for documentation purpose on the generated data for the unittest

Parameters:
  • amplitude – {0, 0.5}

  • noise_gen – a random generator

  • noise – a gaussian noise

  • amplitude – sinus amplitude

  • pulsation – sinus pulsation

  • time – the current time in seconds

Returns:

a noisy sinusoid

TEST_F(TestEKF, simple_1d_ekf_test)

This test evaluates a simple 1d ekf for debugging purpose.

file ukf.hpp
#include <iostream>
#include “Eigen/Eigen”
#include “mim_estimation/standard_filters/ukf.hxx”

Implements the Unscented Kalman Filter (UKF).

License:

BSD 3-clause

The theory is described here. https://www.seas.harvard.edu/courses/cs281/papers/unscented.pdf
Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

Todo:

Explain here the math a little at least or add ref.

file ukf.hxx
#include “mim_estimation/standard_filters/ukf.hpp”

Implements the UKF templated class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file base_ekf_with_imu_kin.hpp
#include <Eigen/StdVector>
#include “pinocchio/multibody/data.hpp”
#include “pinocchio/multibody/model.hpp”

Defines a class implementing a base state estimator using the imu and the kinematics information.

License:

BSD 3-clause

Copyright

Copyright (c) 2021, New York University and Max Planck Gesellschaft

file end_effector_force_estimator.hpp
#include <Eigen/Eigen>
#include “pinocchio/multibody/data.hpp”
#include “pinocchio/multibody/model.hpp”

Computes the forces at the end-effector.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file data_collector.hpp
#include <Eigen/Eigen>
#include <string>
#include <vector>

Abstract interface DataCollector to collect data inside a specific library.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file data_reader.hpp
#include <Eigen/Eigen>

Parser to load SL file format (clmcplot) It loads the data and provide a usueful API for accessing the fields Implement some function to access the data from the SL d-file.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file non_rt_data_collector.hpp
#include <deque>
#include <string>

Collecting data in a non real-time inside a specific library and dump it in the SL format.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file robot_state_estimator.hpp
#include <sstream>

Implement a base state estimator using different classes in this package.

License:

BSD 3-clause

Copyright

Copyright (c) 2021, New York University and Max Planck Gesellschaft

file robot_state_estimator.hpp
#include <dynamic-graph/all-commands.h>
#include <dynamic-graph/all-signals.h>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/linear-algebra.h>
#include <deque>
file butterworth_filter.hpp
#include <Eigen/Dense>
#include <iostream>
#include <vector>

Implements the Butterworth filters. An Introduction to the math can be found here: https://en.wikipedia.org/wiki/Butterworth_filter.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file butterworth_filter.hxx
#include <cmath>
#include <complex>
#include <cstdio>
#include <iomanip>
#include <iostream>
#include <stdexcept>
#include <string>
#include <vector>

Implements the ButterworthFilter temaplated class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file dg_python_module.cpp
#include “dynamic-graph/python/module.hh”
#include “dynamic-graph/python/signal.hh”

Expose the Device and the periodic call to python.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

Typedefs

typedef bp::return_value_policy<bp::reference_existing_object> reference_existing_object

Functions

BOOST_PYTHON_MODULE(entities)
file robot_state_estimator.cpp
#include <iostream>
#include “signal_utils.hpp
file robot_state_estimator.cpp
#include “pinocchio/bindings/python/fwd.hpp”
#include <boost/python.hpp>
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>

Python bindings for the StepperHead class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file signal_utils.cpp
#include “signal_utils.hpp

This is the implementation for impedance controller between any two frames of the robot.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file signal_utils.hpp
#include <sstream>

Utilities for the creation of signals.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

Defines

crop_underscore(var_name)
define_input_signal(signal_var_name, signal_type)
define_output_signal(signal_var_name, signal_type, signal_dep, callback)
define_internal_output_signal(signal_var_name, signal_type, signal_dep, callback)
file base_ekf_with_imu_kin.cpp
#include “pinocchio/bindings/python/fwd.hpp”
#include <boost/python.hpp>
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>

Python bindings for the StepperHead class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file end_effector_force_estimator.cpp
#include “pinocchio/bindings/python/fwd.hpp”
#include <eigenpy/eigenpy.hpp>
#include <boost/python.hpp>
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>

Python bindings for the StepperHead class.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

file mim_estimation.cpp
#include <boost/python.hpp>
#include <boost/python/class.hpp>
#include <eigenpy/eigenpy.hpp>

Python bindings for the mim_estimation package.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

page todo

Class mim_estimation::BaseEkfWithImuKin

explain here the math around the EKF

File ukf.hpp

Explain here the math a little at least or add ref.

page license

File base_ekf_with_imu_kin.cpp

BSD 3-clause

File base_ekf_with_imu_kin.hpp

BSD 3-clause

File butterworth_filter.hpp

BSD 3-clause

File butterworth_filter.hxx

BSD 3-clause

File data_collector.hpp

BSD 3-clause

File data_reader.hpp

BSD 3-clause

File demo_ekf_vicon_imu.cpp

BSD 3-clause

File dg_python_module.cpp

BSD 3-clause

File ekf.hpp

BSD 3-clause

File ekf.hxx

BSD 3-clause

File ekf_vicon_imu_simple.hpp

BSD 3-clause

File end_effector_force_estimator.cpp

BSD 3-clause

File end_effector_force_estimator.hpp

BSD 3-clause

File mim_estimation.cpp

BSD 3-clause

File non_rt_data_collector.hpp

BSD 3-clause

File robot_state_estimator.cpp

BSD 3-clause

File robot_state_estimator.hpp

BSD 3-clause

File signal_utils.cpp

BSD 3-clause

File signal_utils.hpp

BSD 3-clause

File test_ekf_vicon_imu.cpp

BSD 3-clause

File ukf.hpp

BSD 3-clause

File ukf.hxx

BSD 3-clause

dir deprecated
dir include
dir include/mim_estimation/io_tools
dir include/mim_estimation
dir srcdg
dir srcpy
dir include/mim_estimation/standard_filters