#include <SensorHandlers.hpp>

Public Types | |
| enum | { u = 0, v, w } |
Public Member Functions | |
| const double * | body_speeds () const |
| void | configure (ros::NodeHandle &nh) |
| void | current_r (double yaw_rate) |
| DvlHandler () | |
Private Member Functions | |
| void | onDvl (const geometry_msgs::TwistStamped::ConstPtr &data) |
Private Attributes | |
| tf::TransformListener | listener |
| ros::Subscriber | nu_dvl |
| double | r |
| double | uvw [3] |
Definition at line 117 of file SensorHandlers.hpp.
| anonymous enum |
Definition at line 120 of file SensorHandlers.hpp.
| labust::navigation::DvlHandler::DvlHandler | ( | ) | [inline] |
Definition at line 122 of file SensorHandlers.hpp.
| const double* labust::navigation::DvlHandler::body_speeds | ( | ) | const [inline] |
Definition at line 126 of file SensorHandlers.hpp.
| void DvlHandler::configure | ( | ros::NodeHandle & | nh | ) |
Definition at line 113 of file SensorHandlers.cpp.
| void labust::navigation::DvlHandler::current_r | ( | double | yaw_rate | ) | [inline] |
Definition at line 128 of file SensorHandlers.hpp.
| void DvlHandler::onDvl | ( | const geometry_msgs::TwistStamped::ConstPtr & | data | ) | [private] |
Definition at line 121 of file SensorHandlers.cpp.
Definition at line 134 of file SensorHandlers.hpp.
Definition at line 133 of file SensorHandlers.hpp.
double labust::navigation::DvlHandler::r [private] |
Definition at line 132 of file SensorHandlers.hpp.
double labust::navigation::DvlHandler::uvw[3] [private] |
Definition at line 132 of file SensorHandlers.hpp.