Go to the documentation of this file.
36 #ifndef __ODOM_ESTIMATION__
37 #define __ODOM_ESTIMATION__
40 #include <bfl/filter/extendedkalmanfilter.h>
41 #include <bfl/wrappers/matrix/matrix_wrapper.h>
42 #include <bfl/model/linearanalyticsystemmodel_gaussianuncertainty.h>
43 #include <bfl/model/linearanalyticmeasurementmodel_gaussianuncertainty.h>
44 #include <bfl/pdf/analyticconditionalgaussian.h>
45 #include <bfl/pdf/linearanalyticconditionalgaussian.h>
52 #include <geometry_msgs/PoseWithCovarianceStamped.h>
78 bool update(
bool odom_active,
bool imu_active,
bool gps_active,
bool vo_active,
const ros::Time& filter_time,
bool& diagnostics_res);
94 void getEstimate(MatrixWrapper::ColumnVector& estimate);
111 void getEstimate(geometry_msgs::PoseWithCovarianceStamped& estimate);
140 double& x,
double& y,
double&z,
double&Rx,
double& Ry,
double& Rz);
142 double& x,
double& y,
double&z,
double&Rx,
double& Ry,
double& Rz);
146 BFL::AnalyticSystemModelGaussianUncertainty*
sys_model_;
153 BFL::LinearAnalyticMeasurementModelGaussianUncertainty*
vo_meas_model_;
155 BFL::LinearAnalyticMeasurementModelGaussianUncertainty*
gps_meas_model_;
157 BFL::ExtendedKalmanFilter*
filter_;
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * vo_meas_model_
MatrixWrapper::SymmetricMatrix odom_covariance_
tf::Transform filter_estimate_old_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * gps_meas_model_
MatrixWrapper::ColumnVector filter_estimate_old_vec_
Non Linear Conditional Gaussian.
tf::StampedTransform vo_meas_old_
std::string output_frame_
double diagnostics_imu_rot_rel_
tf::StampedTransform gps_meas_old_
void decomposeTransform(const tf::StampedTransform &trans, double &x, double &y, double &z, double &Rx, double &Ry, double &Rz)
BFL::AnalyticSystemModelGaussianUncertainty * sys_model_
tf::Transformer transformer_
MatrixWrapper::SymmetricMatrix gps_covariance_
BFL::NonLinearAnalyticConditionalGaussianOdo * sys_pdf_
MatrixWrapper::SymmetricMatrix imu_covariance_
tf::StampedTransform odom_meas_
BFL::LinearAnalyticConditionalGaussian * imu_meas_pdf_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * odom_meas_model_
MatrixWrapper::SymmetricMatrix vo_covariance_
void angleOverflowCorrect(double &a, double ref)
correct for angle overflow
void setOutputFrame(const std::string &output_frame)
BFL::ExtendedKalmanFilter * filter_
MatrixWrapper::ColumnVector vel_desi_
void getEstimate(MatrixWrapper::ColumnVector &estimate)
void addMeasurement(const tf::StampedTransform &meas)
BFL::LinearAnalyticConditionalGaussian * gps_meas_pdf_
double diagnostics_odom_rot_rel_
tf::StampedTransform imu_meas_
BFL::LinearAnalyticConditionalGaussian * odom_meas_pdf_
tf::StampedTransform imu_meas_old_
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * imu_meas_model_
OdomEstimation()
constructor
std::string base_footprint_frame_
void setBaseFootprintFrame(const std::string &base_frame)
ros::Time filter_time_old_
tf::StampedTransform gps_meas_
bool update(bool odom_active, bool imu_active, bool gps_active, bool vo_active, const ros::Time &filter_time, bool &diagnostics_res)
virtual ~OdomEstimation()
destructor
void initialize(const tf::Transform &prior, const ros::Time &time)
tf::StampedTransform odom_meas_old_
BFL::LinearAnalyticConditionalGaussian * vo_meas_pdf_
tf::StampedTransform vo_meas_
robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Wed Mar 2 2022 00:50:47