Public Member Functions | Private Types | Private Member Functions | Private Attributes
labust::navigation::Estimator3D Class Reference

#include <Estimator3D.hpp>

List of all members.

Public Member Functions

 Estimator3D ()
 Estimator3D ()
void onInit ()
void onInit ()
void start ()
void start ()

Private Types

enum  {
  X = 0, Y, Z, K,
  M, N, DoF
}
enum  {
  X = 0, Y, Z, K,
  M, N, DoF
}
typedef
labust::navigation::KFCore
< labust::navigation::LDTravModel
KFNav
typedef
labust::navigation::KFCore
< labust::navigation::LDTravModel
KFNav

Private Member Functions

void configureNav (KFNav &nav, ros::NodeHandle &nh)
void configureNav (KFNav &nav, ros::NodeHandle &nh)
void onAltitude (const std_msgs::Float32::ConstPtr &data)
void onAltitude (const std_msgs::Float32::ConstPtr &data)
void onDepth (const std_msgs::Float32::ConstPtr &data)
void onDepth (const std_msgs::Float32::ConstPtr &data)
void onModelUpdate (const navcon_msgs::ModelParamsUpdate::ConstPtr &update)
void onModelUpdate (const navcon_msgs::ModelParamsUpdate::ConstPtr &update)
void onTau (const auv_msgs::BodyForceReq::ConstPtr &tau)
void onTau (const auv_msgs::BodyForceReq::ConstPtr &tau)
void processMeasurements ()
void processMeasurements ()
void publishState ()
void publishState ()

Private Attributes

double alt
ros::Subscriber altitude
tf::TransformBroadcaster broadcaster
ros::Publisher currentsHat
ros::Subscriber depth
DvlHandler dvl
int dvl_model
GPSHandler gps
ImuHandler imu
KFNav::vector measurements
ros::Subscriber modelUpdate
KFNav nav
KFNav::vector newMeas
KFNav::ModelParams params [DoF]
ros::Publisher stateHat
ros::Publisher stateMeas
ros::Subscriber tauAch
KFNav::vector tauIn
labust::math::unwrap unwrap
bool useYawRate

Detailed Description

The 3D state estimator for ROVs and AUVs.

Todo:
Extract the lat/lon part into the llnode.

The 3D state estimator for ROVs and AUVs. Extended with altitude and pitch estimates.

Todo:
Extract the lat/lon part into the llnode.

Definition at line 56 of file Estimator3D.hpp.


Member Typedef Documentation

Definition at line 59 of file Estimator3D.hpp.

Definition at line 59 of file Estimator3DExtended.hpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
X 
Y 
Z 
K 
M 
N 
DoF 

Definition at line 58 of file Estimator3D.hpp.

anonymous enum [private]
Enumerator:
X 
Y 
Z 
K 
M 
N 
DoF 

Definition at line 58 of file Estimator3DExtended.hpp.


Constructor & Destructor Documentation

Main constructor.

Definition at line 58 of file Estimator3D.cpp.

Main constructor.


Member Function Documentation

void Estimator3D::configureNav ( KFNav nav,
ros::NodeHandle nh 
) [private]

Helper function for navigation configuration.

Definition at line 92 of file Estimator3D.cpp.

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.

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.

Helper method to process measurements.

Helper method to process measurements.

Definition at line 163 of file Estimator3D.cpp.

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.

Start the estimation loop.

Definition at line 302 of file Estimator3D.cpp.

Start the estimation loop.


Member Data Documentation

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.

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.

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.

The flag to indicate existing yaw-rate measurements.

Definition at line 156 of file Estimator3D.hpp.


The documentation for this class was generated from the following files:


ldtravocean
Author(s):
autogenerated on Fri Feb 7 2014 11:37:01