#include <USBLManager.hpp>
Public Member Functions | |
void | changeState (int next) |
void | onInit () |
USBLManager () | |
~USBLManager () | |
Protected Member Functions | |
void | incoming_def_txt () |
void | incoming_kml () |
void | init_diver () |
std::string | intToMsg (int len) |
void | kml_send () |
int | msgToInt (int len) |
void | onIncomingDefaults (const std_msgs::Int32::ConstPtr msg) |
void | onIncomingForceState (const std_msgs::Int32::ConstPtr msg) |
void | onIncomingKML (const std_msgs::Float64MultiArray::ConstPtr msg) |
void | onIncomingMsg (const std_msgs::String::ConstPtr msg) |
void | onIncomingText (const std_msgs::String::ConstPtr msg) |
void | onNavMsg (const auv_msgs::NavSts::ConstPtr nav) |
void | onUSBLTimeout (const std_msgs::Bool::ConstPtr msg) |
void | publishDiverOrigin () |
void | resendLastPackage () |
void | run () |
void | send_msg () |
Protected Attributes | |
ros::Publisher | auto_mode |
std::queue< char > | defaultMsgs |
std::map< int, boost::function < void(void)> > | dispatch |
ros::Publisher | diverDefaults |
ros::Publisher | diverOrigin |
double | diverOriginLat |
double | diverOriginLon |
ros::Publisher | diverText |
int | emptyIterations |
ros::Subscriber | forceState |
ros::Subscriber | incoming |
DiverMsg | incoming_msg |
std_msgs::String | incoming_package |
ros::Subscriber | inDefaults |
int | initValidation |
ros::Subscriber | inKml |
ros::Subscriber | intext |
std::queue< std::pair< double, double > > | kmlBuffer |
std::pair< int, int > | kmlEndValidation |
std::vector< int > | kmlValidIdx |
std::vector< std::pair< int, int > > | kmlVec |
int | lastKmlIdxSent |
int | lastState |
ros::Subscriber | navData |
bool | newMessage |
ros::Publisher | outCurState |
ros::Publisher | outgoing |
DiverMsg | outgoing_msg |
std_msgs::String | outgoing_package |
ros::Publisher | retKml |
int | state |
std::queue< char > | textBuffer |
int | timeout |
ros::Subscriber | timeoutNotification |
bool | validNav |
boost::thread | worker |
Private Types | |
enum | { idle = 0, initDiver, waitForReply, transmission, lastStateNum } |
enum | { kmlNotSent = 0, kmlSent, kmlWaitValidation, kmlSentAndValid } |
The class implements the Tritech USBL manager that allows specifying which messages and what data to relay to the modem. It also encodes arrived modem messages.
Should we extract message handlers into different class/classes ?
Probably Yes, it is getting messy and heavy
Definition at line 113 of file USBLManager.hpp.
anonymous enum [private] |
The communication states.
Definition at line 118 of file USBLManager.hpp.
anonymous enum [private] |
Definition at line 119 of file USBLManager.hpp.
Default constructor.
Definition at line 50 of file USBLManager.cpp.
Default destructor.
Definition at line 70 of file USBLManager.cpp.
void labust::tritech::USBLManager::changeState | ( | int | next | ) | [inline] |
State changer.
Definition at line 138 of file USBLManager.hpp.
void USBLManager::incoming_def_txt | ( | ) | [protected] |
Helper function for handling incoming text messages.
Definition at line 142 of file USBLManager.cpp.
void USBLManager::incoming_kml | ( | ) | [protected] |
Incoming KML message.
Definition at line 179 of file USBLManager.cpp.
void USBLManager::init_diver | ( | ) | [protected] |
Helper function for initialization.
Definition at line 93 of file USBLManager.cpp.
std::string USBLManager::intToMsg | ( | int | len | ) | [protected] |
Helper function for message decoding from int.
Definition at line 211 of file USBLManager.cpp.
void USBLManager::kml_send | ( | ) | [protected] |
Kml message send handler.
Definition at line 301 of file USBLManager.cpp.
int USBLManager::msgToInt | ( | int | len | ) | [protected] |
Helper function for message encoding to int.
Definition at line 226 of file USBLManager.cpp.
void USBLManager::onIncomingDefaults | ( | const std_msgs::Int32::ConstPtr | msg | ) | [protected] |
Handles the incoming default messages.
Definition at line 556 of file USBLManager.cpp.
void USBLManager::onIncomingForceState | ( | const std_msgs::Int32::ConstPtr | msg | ) | [protected] |
Handles the incoming default messages.
Definition at line 562 of file USBLManager.cpp.
void USBLManager::onIncomingKML | ( | const std_msgs::Float64MultiArray::ConstPtr | msg | ) | [protected] |
Handles the incoming KML messages.
Definition at line 575 of file USBLManager.cpp.
void USBLManager::onIncomingMsg | ( | const std_msgs::String::ConstPtr | msg | ) | [protected] |
Handles arrived modem messages.
Definition at line 496 of file USBLManager.cpp.
void USBLManager::onIncomingText | ( | const std_msgs::String::ConstPtr | msg | ) | [protected] |
Handles arrived modem messages.
Definition at line 526 of file USBLManager.cpp.
void USBLManager::onInit | ( | ) | [virtual] |
void USBLManager::onNavMsg | ( | const auv_msgs::NavSts::ConstPtr | nav | ) | [protected] |
Handles arrived USBL navigation messages.
Definition at line 487 of file USBLManager.cpp.
void USBLManager::onUSBLTimeout | ( | const std_msgs::Bool::ConstPtr | msg | ) | [protected] |
Handles the USBL timeout.
Definition at line 534 of file USBLManager.cpp.
void USBLManager::publishDiverOrigin | ( | ) | [protected] |
Helper diver origin publisher.
Definition at line 593 of file USBLManager.cpp.
void USBLManager::resendLastPackage | ( | ) | [protected] |
Helper function for resending the last package.
Definition at line 543 of file USBLManager.cpp.
void USBLManager::run | ( | ) | [protected] |
The main runner thread.
Switch all automata like this to a boost state chart or something to avoid switch
Switch the manager to async triggered instead of having a run method.
Definition at line 441 of file USBLManager.cpp.
void USBLManager::send_msg | ( | ) | [protected] |
Helper function for message sending.
Definition at line 243 of file USBLManager.cpp.
Definition at line 222 of file USBLManager.hpp.
std::queue<char> labust::tritech::USBLManager::defaultMsgs [protected] |
The preset messages buffer.
Definition at line 260 of file USBLManager.hpp.
std::map<int, boost::function<void(void)> > labust::tritech::USBLManager::dispatch [protected] |
Message decoder dispatcher.
Definition at line 289 of file USBLManager.hpp.
Definition at line 222 of file USBLManager.hpp.
Definition at line 222 of file USBLManager.hpp.
double labust::tritech::USBLManager::diverOriginLat [protected] |
The diver frame origin.
Definition at line 297 of file USBLManager.hpp.
double labust::tritech::USBLManager::diverOriginLon [protected] |
Definition at line 297 of file USBLManager.hpp.
Definition at line 222 of file USBLManager.hpp.
int labust::tritech::USBLManager::emptyIterations [protected] |
Definition at line 293 of file USBLManager.hpp.
Definition at line 227 of file USBLManager.hpp.
Definition at line 227 of file USBLManager.hpp.
DiverMsg labust::tritech::USBLManager::incoming_msg [protected] |
Definition at line 248 of file USBLManager.hpp.
std_msgs::String labust::tritech::USBLManager::incoming_package [protected] |
Definition at line 252 of file USBLManager.hpp.
Definition at line 227 of file USBLManager.hpp.
int labust::tritech::USBLManager::initValidation [protected] |
The init validation.
Definition at line 281 of file USBLManager.hpp.
ros::Subscriber labust::tritech::USBLManager::inKml [protected] |
Definition at line 227 of file USBLManager.hpp.
ros::Subscriber labust::tritech::USBLManager::intext [protected] |
Definition at line 227 of file USBLManager.hpp.
std::queue< std::pair<double, double> > labust::tritech::USBLManager::kmlBuffer [protected] |
The incoming kml queue.
Definition at line 264 of file USBLManager.hpp.
std::pair<int, int> labust::tritech::USBLManager::kmlEndValidation [protected] |
The default and next kml message validation. The pair is <validation_flag, expected message>.
Definition at line 277 of file USBLManager.hpp.
std::vector<int> labust::tritech::USBLManager::kmlValidIdx [protected] |
The validated kml indexes.
Definition at line 272 of file USBLManager.hpp.
std::vector< std::pair<int, int> > labust::tritech::USBLManager::kmlVec [protected] |
The current kml transmit buffer.
Definition at line 268 of file USBLManager.hpp.
int labust::tritech::USBLManager::lastKmlIdxSent [protected] |
The last kml debugging output.
Definition at line 301 of file USBLManager.hpp.
int labust::tritech::USBLManager::lastState [protected] |
Definition at line 240 of file USBLManager.hpp.
ros::Subscriber labust::tritech::USBLManager::navData [protected] |
The navigation data subscription.
Definition at line 227 of file USBLManager.hpp.
bool labust::tritech::USBLManager::newMessage [protected] |
Flag for the turnaround message.
Definition at line 285 of file USBLManager.hpp.
Definition at line 222 of file USBLManager.hpp.
ros::Publisher labust::tritech::USBLManager::outgoing [protected] |
The navigation and incoming data publisher.
Definition at line 222 of file USBLManager.hpp.
DiverMsg labust::tritech::USBLManager::outgoing_msg [protected] |
The diver message encoder.
Definition at line 248 of file USBLManager.hpp.
std_msgs::String labust::tritech::USBLManager::outgoing_package [protected] |
The last sent package.
Definition at line 252 of file USBLManager.hpp.
ros::Publisher labust::tritech::USBLManager::retKml [protected] |
Definition at line 222 of file USBLManager.hpp.
int labust::tritech::USBLManager::state [protected] |
The current comms state.
Definition at line 240 of file USBLManager.hpp.
std::queue<char> labust::tritech::USBLManager::textBuffer [protected] |
Text message buffer.
Definition at line 256 of file USBLManager.hpp.
int labust::tritech::USBLManager::timeout [protected] |
Internal timeout in iterations and general counter.
Definition at line 293 of file USBLManager.hpp.
Definition at line 227 of file USBLManager.hpp.
bool labust::tritech::USBLManager::validNav [protected] |
Navigation message flag.
Definition at line 244 of file USBLManager.hpp.
boost::thread labust::tritech::USBLManager::worker [protected] |
The message encoder. The worker thread.
Definition at line 236 of file USBLManager.hpp.