Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
labust::tritech::USBLFilter Class Reference

#include <USBLFilter.hpp>

Inheritance diagram for labust::tritech::USBLFilter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void onInit ()
void run ()
 USBLFilter ()
 ~USBLFilter ()

Protected Member Functions

void configureModel (ros::NodeHandle &nh)
void onUsbl (const geometry_msgs::PointStamped::ConstPtr &msg)

Protected Attributes

boost::mutex dataMux
double depth
KFilter filter
int iteration
tf::TransformListener listener
double maxSpeed
ros::Publisher navPub
int timeout
ros::Subscriber usblSub
boost::thread worker

Private Types

typedef
labust::navigation::KFCore
< labust::navigation::KinematicModel
KFilter

Detailed Description

The class implements the Tritech USBL acquisition nodelet.

Definition at line 58 of file USBLFilter.hpp.


Member Typedef Documentation

Definition at line 60 of file USBLFilter.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 50 of file USBLFilter.cpp.

Default destructor.

Definition at line 55 of file USBLFilter.cpp.


Member Function Documentation

void USBLFilter::configureModel ( ros::NodeHandle nh) [protected]

Configure from ROS file.

Definition at line 68 of file USBLFilter.cpp.

void USBLFilter::onInit ( ) [virtual]

Node initialization.

Implements nodelet::Nodelet.

Definition at line 57 of file USBLFilter.cpp.

void USBLFilter::onUsbl ( const geometry_msgs::PointStamped::ConstPtr &  msg) [protected]

Handles arrived USBL navigation messages.

Definition at line 106 of file USBLFilter.cpp.

void USBLFilter::run ( )

The main run method.

Todo:
Add variable rate of filter estimates.

Definition at line 155 of file USBLFilter.cpp.


Member Data Documentation

boost::mutex labust::tritech::USBLFilter::dataMux [protected]

The data and condition mux.

Definition at line 101 of file USBLFilter.hpp.

The depth state.

Definition at line 97 of file USBLFilter.hpp.

The USBL device.

Definition at line 93 of file USBLFilter.hpp.

Definition at line 123 of file USBLFilter.hpp.

Frame transform listener.

Definition at line 119 of file USBLFilter.hpp.

Maximum diver speed.

Definition at line 127 of file USBLFilter.hpp.

The navigation publisher.

Definition at line 111 of file USBLFilter.hpp.

Safety timeout.

Definition at line 123 of file USBLFilter.hpp.

The usbl measurement subscriber.

Definition at line 115 of file USBLFilter.hpp.

boost::thread labust::tritech::USBLFilter::worker [protected]

The worker thread.

Definition at line 106 of file USBLFilter.hpp.


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


usbl
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:29