#include <USBLNodelet.hpp>
Public Member Functions | |
void | onInit () |
void | run () |
void | stop () |
USBLNodelet () | |
~USBLNodelet () | |
Protected Member Functions | |
void | onAttMsg (labust::tritech::TCONMsgPtr tmsg) |
void | onAutoMode (const std_msgs::Bool::ConstPtr mode) |
void | onNavMsg (labust::tritech::TCONMsgPtr tmsg) |
void | onOutgoingMsg (const std_msgs::String::ConstPtr msg) |
void | onTCONMsg (labust::tritech::TCONMsgPtr tmsg) |
void | sendUSBLPkg () |
Protected Attributes | |
std::string | address |
ros::Publisher | attData |
TCPDevicePtr | attitude |
ros::Publisher | attRaw |
bool | autoMode |
boost::mutex | dataMux |
ros::Publisher | dataPub |
ros::Subscriber | dataSub |
tf::TransformBroadcaster | frameBroadcast |
boost::thread | guard |
ros::Time | lastUSBL |
std::string | msg_out |
ros::Publisher | navPub |
ros::Subscriber | opMode |
int | ping_timeout |
boost::mutex | pingLock |
int | port |
TCPDevicePtr | usbl |
bool | usblBusy |
boost::condition_variable | usblCondition |
ros::Publisher | usblTimeout |
boost::thread | worker |
The class implements the Tritech USBL acquisition nodelet.
Definition at line 58 of file USBLNodelet.hpp.
Default constructor.
Definition at line 53 of file USBLNodelet.cpp.
Default destructor.
Definition at line 60 of file USBLNodelet.cpp.
void USBLNodelet::onAttMsg | ( | labust::tritech::TCONMsgPtr | tmsg | ) | [protected] |
Handles arrived USBL navigation messages.
Definition at line 149 of file USBLNodelet.cpp.
void USBLNodelet::onAutoMode | ( | const std_msgs::Bool::ConstPtr | mode | ) | [protected] |
Handles outgoing messages requests.
Definition at line 112 of file USBLNodelet.cpp.
void USBLNodelet::onInit | ( | ) | [virtual] |
void USBLNodelet::onNavMsg | ( | labust::tritech::TCONMsgPtr | tmsg | ) | [protected] |
Handles arrived USBL navigation messages.
Definition at line 170 of file USBLNodelet.cpp.
void USBLNodelet::onOutgoingMsg | ( | const std_msgs::String::ConstPtr | msg | ) | [protected] |
Handles outgoing messages requests.
Definition at line 130 of file USBLNodelet.cpp.
void USBLNodelet::onTCONMsg | ( | labust::tritech::TCONMsgPtr | tmsg | ) | [protected] |
Handles other USBL messages.
Definition at line 137 of file USBLNodelet.cpp.
void USBLNodelet::run | ( | ) |
The main run method.
Definition at line 272 of file USBLNodelet.cpp.
void USBLNodelet::sendUSBLPkg | ( | ) | [protected] |
Send one USBL encoded package.
Definition at line 231 of file USBLNodelet.cpp.
void USBLNodelet::stop | ( | ) |
Cleanly stops the main method but leaves on the USBL connection.
Definition at line 101 of file USBLNodelet.cpp.
std::string labust::tritech::USBLNodelet::address [protected] |
The USBL address.
Definition at line 121 of file USBLNodelet.hpp.
ros::Publisher labust::tritech::USBLNodelet::attData [protected] |
Definition at line 155 of file USBLNodelet.hpp.
TCPDevicePtr labust::tritech::USBLNodelet::attitude [protected] |
Definition at line 117 of file USBLNodelet.hpp.
ros::Publisher labust::tritech::USBLNodelet::attRaw [protected] |
Definition at line 155 of file USBLNodelet.hpp.
bool labust::tritech::USBLNodelet::autoMode [protected] |
Auto interrogate mode.
Definition at line 167 of file USBLNodelet.hpp.
boost::mutex labust::tritech::USBLNodelet::dataMux [protected] |
The data and condition mux.
Definition at line 146 of file USBLNodelet.hpp.
ros::Publisher labust::tritech::USBLNodelet::dataPub [protected] |
Definition at line 155 of file USBLNodelet.hpp.
ros::Subscriber labust::tritech::USBLNodelet::dataSub [protected] |
The outgoing data subscription.
Definition at line 159 of file USBLNodelet.hpp.
USBL frame transformation broadcaster.
Definition at line 163 of file USBLNodelet.hpp.
boost::thread labust::tritech::USBLNodelet::guard [protected] |
Definition at line 150 of file USBLNodelet.hpp.
ros::Time labust::tritech::USBLNodelet::lastUSBL [protected] |
Last message from USBL.
Definition at line 129 of file USBLNodelet.hpp.
std::string labust::tritech::USBLNodelet::msg_out [protected] |
The outgoing message.
Definition at line 133 of file USBLNodelet.hpp.
ros::Publisher labust::tritech::USBLNodelet::navPub [protected] |
The navigation and incoming data publisher.
Definition at line 155 of file USBLNodelet.hpp.
ros::Subscriber labust::tritech::USBLNodelet::opMode [protected] |
Definition at line 159 of file USBLNodelet.hpp.
int labust::tritech::USBLNodelet::ping_timeout [protected] |
Ping timeout.
Definition at line 112 of file USBLNodelet.hpp.
boost::mutex labust::tritech::USBLNodelet::pingLock [protected] |
Definition at line 146 of file USBLNodelet.hpp.
int labust::tritech::USBLNodelet::port [protected] |
The USBL port.
Definition at line 125 of file USBLNodelet.hpp.
TCPDevicePtr labust::tritech::USBLNodelet::usbl [protected] |
The USBL device.
Definition at line 117 of file USBLNodelet.hpp.
bool labust::tritech::USBLNodelet::usblBusy [protected] |
The USBL status.
Definition at line 137 of file USBLNodelet.hpp.
boost::condition_variable labust::tritech::USBLNodelet::usblCondition [protected] |
The lock condition variable.
Definition at line 141 of file USBLNodelet.hpp.
Definition at line 155 of file USBLNodelet.hpp.
boost::thread labust::tritech::USBLNodelet::worker [protected] |
The worker thread.
Definition at line 150 of file USBLNodelet.hpp.