#include <odom_estimation.h>
|
void | angleOverflowCorrect (double &a, double ref) |
| correct for angle overflow More...
|
|
void | decomposeTransform (const tf::StampedTransform &trans, double &x, double &y, double &z, double &Rx, double &Ry, double &Rz) |
|
void | decomposeTransform (const tf::Transform &trans, double &x, double &y, double &z, double &Rx, double &Ry, double &Rz) |
|
Definition at line 60 of file odom_estimation.h.
estimation::OdomEstimation::OdomEstimation |
( |
| ) |
|
estimation::OdomEstimation::~OdomEstimation |
( |
| ) |
|
|
virtual |
Add a sensor measurement to the measurement buffer
- Parameters
-
meas | the measurement to add |
Definition at line 322 of file odom_estimation.cpp.
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 |
Definition at line 332 of file odom_estimation.cpp.
void estimation::OdomEstimation::angleOverflowCorrect |
( |
double & |
a, |
|
|
double |
ref |
|
) |
| |
|
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::decomposeTransform |
( |
const tf::Transform & |
trans, |
|
|
double & |
x, |
|
|
double & |
y, |
|
|
double & |
z, |
|
|
double & |
Rx, |
|
|
double & |
Ry, |
|
|
double & |
Rz |
|
) |
| |
|
private |
void estimation::OdomEstimation::getEstimate |
( |
MatrixWrapper::ColumnVector & |
estimate | ) |
|
get the filter posterior
- Parameters
-
estimate | the filter posterior as a columnvector |
Definition at line 352 of file odom_estimation.cpp.
get the filter posterior
- Parameters
-
time | the time of the filter posterior |
estimate | the filter posterior as a tf transform |
Definition at line 358 of file odom_estimation.cpp.
get the filter posterior
- Parameters
-
time | the time of the filter posterior |
estimate | the filter posterior as a stamped tf transform |
Definition at line 370 of file odom_estimation.cpp.
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 380 of file odom_estimation.cpp.
initialize the extended Kalman filter
- Parameters
-
prior | the prior robot pose |
time | the initial time of the ekf |
Definition at line 129 of file odom_estimation.cpp.
bool estimation::OdomEstimation::isInitialized |
( |
| ) |
|
|
inline |
check if the filter is initialized returns true if the ekf has been initialized already
Definition at line 89 of file odom_estimation.h.
void estimation::OdomEstimation::setBaseFootprintFrame |
( |
const std::string & |
base_frame | ) |
|
set the base_footprint frame of the robot used by tf
- Parameters
-
base_frame | the desired base frame from which to transform when publishing the combined odometry frame (e.g., base_footprint) |
Definition at line 431 of file odom_estimation.cpp.
void estimation::OdomEstimation::setOutputFrame |
( |
const std::string & |
output_frame | ) |
|
set the output frame used by tf
- Parameters
-
output_frame | the desired output frame published on /tf (e.g., odom_combined) |
Definition at line 427 of file odom_estimation.cpp.
bool estimation::OdomEstimation::update |
( |
bool |
odom_active, |
|
|
bool |
imu_active, |
|
|
bool |
gps_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 |
gps_active | specifies if the gps 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 |
Definition at line 159 of file odom_estimation.cpp.
std::string estimation::OdomEstimation::base_footprint_frame_ |
|
private |
double estimation::OdomEstimation::diagnostics_imu_rot_rel_ |
|
private |
double estimation::OdomEstimation::diagnostics_odom_rot_rel_ |
|
private |
MatrixWrapper::ColumnVector estimation::OdomEstimation::filter_estimate_old_vec_ |
|
private |
bool estimation::OdomEstimation::filter_initialized_ |
|
private |
ros::Time estimation::OdomEstimation::filter_time_old_ |
|
private |
MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::gps_covariance_ |
|
private |
bool estimation::OdomEstimation::gps_initialized_ |
|
private |
MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::imu_covariance_ |
|
private |
bool estimation::OdomEstimation::imu_initialized_ |
|
private |
MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::odom_covariance_ |
|
private |
bool estimation::OdomEstimation::odom_initialized_ |
|
private |
std::string estimation::OdomEstimation::output_frame_ |
|
private |
MatrixWrapper::ColumnVector estimation::OdomEstimation::vel_desi_ |
|
private |
MatrixWrapper::SymmetricMatrix estimation::OdomEstimation::vo_covariance_ |
|
private |
bool estimation::OdomEstimation::vo_initialized_ |
|
private |
The documentation for this class was generated from the following files: