estimation::OdomEstimation Class Reference

#include <odom_estimation.h>

List of all members.

Public Member Functions

void addMeasurement (const tf::StampedTransform &meas, const MatrixWrapper::SymmetricMatrix &covar)
void addMeasurement (const tf::StampedTransform &meas)
void getEstimate (geometry_msgs::PoseWithCovarianceStamped &estimate)
void getEstimate (ros::Time time, tf::StampedTransform &estiamte)
void getEstimate (ros::Time time, tf::Transform &estiamte)
void getEstimate (MatrixWrapper::ColumnVector &estimate)
void initialize (const tf::Transform &prior, const ros::Time &time)
bool isInitialized ()
 OdomEstimation ()
 constructor
bool update (bool odom_active, bool imu_active, bool vo_active, const ros::Time &filter_time, bool &diagnostics_res)
virtual ~OdomEstimation ()
 destructor

Private Member Functions

void angleOverflowCorrect (double &a, double ref)
 correct for angle overflow
void decomposeTransform (const tf::Transform &trans, double &x, double &y, double &z, double &Rx, double &Ry, double &Rz)
void decomposeTransform (const tf::StampedTransform &trans, double &x, double &y, double &z, double &Rx, double &Ry, double &Rz)

Private Attributes

double diagnostics_imu_rot_rel_
double diagnostics_odom_rot_rel_
BFL::ExtendedKalmanFilter * filter_
tf::Transform filter_estimate_old_
MatrixWrapper::ColumnVector filter_estimate_old_vec_
bool filter_initialized_
ros::Time filter_time_old_
MatrixWrapper::SymmetricMatrix imu_covariance_
bool imu_initialized_
tf::StampedTransform imu_meas_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * imu_meas_model_
tf::StampedTransform imu_meas_old_
BFL::LinearAnalyticConditionalGaussian * imu_meas_pdf_
MatrixWrapper::SymmetricMatrix odom_covariance_
bool odom_initialized_
tf::StampedTransform odom_meas_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * odom_meas_model_
tf::StampedTransform odom_meas_old_
BFL::LinearAnalyticConditionalGaussian * odom_meas_pdf_
BFL::Gaussian * prior_
BFL::AnalyticSystemModelGaussianUncertainty * sys_model_
BFL::NonLinearAnalyticConditionalGaussianOdosys_pdf_
tf::Transformer transformer_
MatrixWrapper::ColumnVector vel_desi_
MatrixWrapper::SymmetricMatrix vo_covariance_
bool vo_initialized_
tf::StampedTransform vo_meas_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * vo_meas_model_
tf::StampedTransform vo_meas_old_
BFL::LinearAnalyticConditionalGaussian * vo_meas_pdf_

Detailed Description

Definition at line 55 of file odom_estimation.h.


Constructor & Destructor Documentation

estimation::OdomEstimation::OdomEstimation (  ) 

constructor

Definition at line 49 of file odom_estimation.cpp.

estimation::OdomEstimation::~OdomEstimation (  )  [virtual]

destructor

Definition at line 99 of file odom_estimation.cpp.


Member Function Documentation

void estimation::OdomEstimation::addMeasurement ( const tf::StampedTransform &  meas,
const MatrixWrapper::SymmetricMatrix &  covar 
)

Add a sensor measurement to the measurement buffer

Parameters:
meas the measurement to add
covar the 6x6 covariance matrix of this measurement, as defined in the PoseWithCovariance message
void estimation::OdomEstimation::addMeasurement ( const tf::StampedTransform &  meas  ) 

Add a sensor measurement to the measurement buffer

Parameters:
meas the measurement to add
void estimation::OdomEstimation::angleOverflowCorrect ( double &  a,
double  ref 
) [private]

correct for angle overflow

Definition at line 360 of file odom_estimation.cpp.

void estimation::OdomEstimation::decomposeTransform ( const tf::Transform &  trans,
double &  x,
double &  y,
double &  z,
double &  Rx,
double &  Ry,
double &  Rz 
) [private]
void estimation::OdomEstimation::decomposeTransform ( const tf::StampedTransform &  trans,
double &  x,
double &  y,
double &  z,
double &  Rx,
double &  Ry,
double &  Rz 
) [private]
void estimation::OdomEstimation::getEstimate ( geometry_msgs::PoseWithCovarianceStamped &  estimate  ) 

get the filter posterior

Parameters:
estimate the filter posterior as a pose with covariance

Definition at line 337 of file odom_estimation.cpp.

void estimation::OdomEstimation::getEstimate ( ros::Time  time,
tf::StampedTransform &  estiamte 
)

get the filter posterior

Parameters:
time the time of the filter posterior
estimate the filter posterior as a stamped tf transform
void estimation::OdomEstimation::getEstimate ( ros::Time  time,
tf::Transform &  estiamte 
)

get the filter posterior

Parameters:
time the time of the filter posterior
estimate the filter posterior as a tf transform
void estimation::OdomEstimation::getEstimate ( MatrixWrapper::ColumnVector &  estimate  ) 

get the filter posterior

Parameters:
estimate the filter posterior as a columnvector
void estimation::OdomEstimation::initialize ( const tf::Transform &  prior,
const ros::Time &  time 
)

initialize the extended Kalman filter

Parameters:
prior the prior robot pose
time the initial time of the ekf
bool estimation::OdomEstimation::isInitialized (  )  [inline]

check if the filter is initialized returns true if the ekf has been initialized already

Definition at line 80 of file odom_estimation.h.

bool estimation::OdomEstimation::update ( bool  odom_active,
bool  imu_active,
bool  vo_active,
const ros::Time &  filter_time,
bool &  diagnostics_res 
)

update the extended Kalman filter

Parameters:
odom_active specifies if the odometry sensor is active or not
imu_active specifies if the imu sensor is active or not
vo_active specifies if the vo sensor is active or not
filter_time update the ekf up to this time
diagnostics_res returns false if the diagnostics found that the sensor measurements are inconsistent returns true on successfull update

Member Data Documentation

Definition at line 147 of file odom_estimation.h.

Definition at line 147 of file odom_estimation.h.

BFL::ExtendedKalmanFilter* estimation::OdomEstimation::filter_ [private]

Definition at line 136 of file odom_estimation.h.

Definition at line 141 of file odom_estimation.h.

MatrixWrapper::ColumnVector estimation::OdomEstimation::filter_estimate_old_vec_ [private]

Definition at line 140 of file odom_estimation.h.

Definition at line 144 of file odom_estimation.h.

Definition at line 143 of file odom_estimation.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::imu_covariance_ [private]

Definition at line 137 of file odom_estimation.h.

Definition at line 144 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::imu_meas_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticMeasurementModelGaussianUncertainty* estimation::OdomEstimation::imu_meas_model_ [private]

Definition at line 132 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::imu_meas_old_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticConditionalGaussian* estimation::OdomEstimation::imu_meas_pdf_ [private]

Definition at line 131 of file odom_estimation.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::odom_covariance_ [private]

Definition at line 137 of file odom_estimation.h.

Definition at line 144 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::odom_meas_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticMeasurementModelGaussianUncertainty* estimation::OdomEstimation::odom_meas_model_ [private]

Definition at line 130 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::odom_meas_old_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticConditionalGaussian* estimation::OdomEstimation::odom_meas_pdf_ [private]

Definition at line 129 of file odom_estimation.h.

BFL::Gaussian* estimation::OdomEstimation::prior_ [private]

Definition at line 135 of file odom_estimation.h.

BFL::AnalyticSystemModelGaussianUncertainty* estimation::OdomEstimation::sys_model_ [private]

Definition at line 127 of file odom_estimation.h.

Definition at line 128 of file odom_estimation.h.

tf::Transformer estimation::OdomEstimation::transformer_ [private]

Definition at line 150 of file odom_estimation.h.

MatrixWrapper::ColumnVector estimation::OdomEstimation::vel_desi_ [private]

Definition at line 140 of file odom_estimation.h.

MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::vo_covariance_ [private]

Definition at line 137 of file odom_estimation.h.

Definition at line 144 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::vo_meas_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticMeasurementModelGaussianUncertainty* estimation::OdomEstimation::vo_meas_model_ [private]

Definition at line 134 of file odom_estimation.h.

tf::StampedTransform estimation::OdomEstimation::vo_meas_old_ [private]

Definition at line 142 of file odom_estimation.h.

BFL::LinearAnalyticConditionalGaussian* estimation::OdomEstimation::vo_meas_pdf_ [private]

Definition at line 133 of file odom_estimation.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Fri Jan 11 10:07:53 2013