#include <Estimator3D.hpp>
The 3D state estimator for ROVs and AUVs.
The 3D state estimator for ROVs and AUVs. Extended with altitude and pitch estimates.
Definition at line 56 of file Estimator3D.hpp.
typedef labust::navigation::KFCore<labust::navigation::LDTravModel> labust::navigation::Estimator3D::KFNav [private] |
Definition at line 59 of file Estimator3D.hpp.
typedef labust::navigation::KFCore<labust::navigation::LDTravModel> labust::navigation::Estimator3D::KFNav [private] |
Definition at line 59 of file Estimator3DExtended.hpp.
anonymous enum [private] |
Definition at line 58 of file Estimator3D.hpp.
anonymous enum [private] |
Definition at line 58 of file Estimator3DExtended.hpp.
Main constructor.
Definition at line 58 of file Estimator3D.cpp.
Main constructor.
void Estimator3D::configureNav | ( | KFNav & | nav, |
ros::NodeHandle & | nh | ||
) | [private] |
Helper function for navigation configuration.
Definition at line 92 of file Estimator3D.cpp.
void labust::navigation::Estimator3D::configureNav | ( | KFNav & | nav, |
ros::NodeHandle & | nh | ||
) | [private] |
Helper function for navigation configuration.
void labust::navigation::Estimator3D::onAltitude | ( | const std_msgs::Float32::ConstPtr & | data | ) | [private] |
Handle the altitude measurement.
void Estimator3D::onAltitude | ( | const std_msgs::Float32::ConstPtr & | data | ) | [private] |
Handle the altitude measurement.
Definition at line 156 of file Estimator3D.cpp.
void Estimator3D::onDepth | ( | const std_msgs::Float32::ConstPtr & | data | ) | [private] |
Handle the depth measurement.
Definition at line 150 of file Estimator3D.cpp.
void labust::navigation::Estimator3D::onDepth | ( | const std_msgs::Float32::ConstPtr & | data | ) | [private] |
Handle the depth measurement.
Initialize the estimation filter.
void Estimator3D::onInit | ( | ) |
Initialize the estimation filter.
Definition at line 66 of file Estimator3D.cpp.
void Estimator3D::onModelUpdate | ( | const navcon_msgs::ModelParamsUpdate::ConstPtr & | update | ) | [private] |
On model updates.
Definition at line 124 of file Estimator3D.cpp.
void labust::navigation::Estimator3D::onModelUpdate | ( | const navcon_msgs::ModelParamsUpdate::ConstPtr & | update | ) | [private] |
On model updates.
void Estimator3D::onTau | ( | const auv_msgs::BodyForceReq::ConstPtr & | tau | ) | [private] |
Handle input forces and torques.
Definition at line 142 of file Estimator3D.cpp.
void labust::navigation::Estimator3D::onTau | ( | const auv_msgs::BodyForceReq::ConstPtr & | tau | ) | [private] |
Handle input forces and torques.
void labust::navigation::Estimator3D::processMeasurements | ( | ) | [private] |
Helper method to process measurements.
void Estimator3D::processMeasurements | ( | ) | [private] |
Helper method to process measurements.
Definition at line 163 of file Estimator3D.cpp.
void labust::navigation::Estimator3D::publishState | ( | ) | [private] |
Helper method to publish the navigation state.
void Estimator3D::publishState | ( | ) | [private] |
Helper method to publish the navigation state.
Definition at line 253 of file Estimator3D.cpp.
void Estimator3D::start | ( | ) |
Start the estimation loop.
Definition at line 302 of file Estimator3D.cpp.
Start the estimation loop.
double labust::navigation::Estimator3D::alt [private] |
Temporary altitude storage.
Definition at line 148 of file Estimator3D.hpp.
Definition at line 128 of file Estimator3D.hpp.
The transform broadcaster.
Definition at line 144 of file Estimator3D.hpp.
Definition at line 124 of file Estimator3D.hpp.
Definition at line 128 of file Estimator3D.hpp.
The DVL handler.
Definition at line 140 of file Estimator3D.hpp.
int labust::navigation::Estimator3D::dvl_model [private] |
The DVL model selector.
Definition at line 160 of file Estimator3D.hpp.
The GPS handler.
Definition at line 132 of file Estimator3D.hpp.
The Imu handler.
Definition at line 136 of file Estimator3D.hpp.
The measurements vector and arrived flag vector.
Definition at line 116 of file Estimator3D.hpp.
Definition at line 128 of file Estimator3D.hpp.
KFNav labust::navigation::Estimator3D::nav [private] |
The navigation filter.
Definition at line 108 of file Estimator3D.hpp.
Definition at line 116 of file Estimator3D.hpp.
KFNav::ModelParams labust::navigation::Estimator3D::params [private] |
Model parameters
Definition at line 152 of file Estimator3D.hpp.
Definition at line 124 of file Estimator3D.hpp.
Estimated and measured state publisher.
Definition at line 124 of file Estimator3D.hpp.
Sensors and input subscribers.
Definition at line 128 of file Estimator3D.hpp.
The input vector.
Definition at line 112 of file Estimator3D.hpp.
Heading unwrapper.
Definition at line 120 of file Estimator3D.hpp.
bool labust::navigation::Estimator3D::useYawRate [private] |
The flag to indicate existing yaw-rate measurements.
Definition at line 156 of file Estimator3D.hpp.