Public Member Functions | |
| void | onDiverSim (const auv_msgs::NavSts::ConstPtr msg) |
| void | onOutgoingMsg (const std_msgs::String::ConstPtr msg) |
| void | onPlatformSim (const auv_msgs::NavSts::ConstPtr msg) |
| void | onReplyMsg (labust::tritech::MTMsgPtr tmsg) |
| USBLSim () | |
Public Attributes | |
| ros::Publisher | dataPub |
| ros::Subscriber | dataSub |
| ros::Time | lastNav |
| double | navTime |
| boost::mutex | pingLock |
| std::queue< std_msgs::String > | reply_queue |
| bool | sent |
| ros::Subscriber | simDiverState |
| ros::Subscriber | simVehicleState |
| boost::shared_ptr < labust::tritech::MTDevice > | usbl |
| bool | usblBusy |
| boost::condition_variable | usblCondition |
| ros::Publisher | usblNav |
| ros::Publisher | usblTimeout |
| bool | useDevice |
| auv_msgs::NavSts | vehicleState |
| boost::mutex | vehicleStateMux |
Definition at line 55 of file usbl_sim.cpp.
| USBLSim::USBLSim | ( | ) | [inline] |
Definition at line 58 of file usbl_sim.cpp.
| void USBLSim::onDiverSim | ( | const auv_msgs::NavSts::ConstPtr | msg | ) | [inline] |
Definition at line 115 of file usbl_sim.cpp.
| void USBLSim::onOutgoingMsg | ( | const std_msgs::String::ConstPtr | msg | ) | [inline] |
Definition at line 135 of file usbl_sim.cpp.
| void USBLSim::onPlatformSim | ( | const auv_msgs::NavSts::ConstPtr | msg | ) | [inline] |
Definition at line 121 of file usbl_sim.cpp.
| void USBLSim::onReplyMsg | ( | labust::tritech::MTMsgPtr | tmsg | ) | [inline] |
Definition at line 90 of file usbl_sim.cpp.
Definition at line 172 of file usbl_sim.cpp.
Definition at line 173 of file usbl_sim.cpp.
Definition at line 182 of file usbl_sim.cpp.
| double USBLSim::navTime |
Definition at line 181 of file usbl_sim.cpp.
| boost::mutex USBLSim::pingLock |
Definition at line 176 of file usbl_sim.cpp.
| std::queue<std_msgs::String> USBLSim::reply_queue |
Definition at line 179 of file usbl_sim.cpp.
| bool USBLSim::sent |
Definition at line 180 of file usbl_sim.cpp.
Definition at line 173 of file usbl_sim.cpp.
Definition at line 173 of file usbl_sim.cpp.
| boost::shared_ptr<labust::tritech::MTDevice> USBLSim::usbl |
Definition at line 175 of file usbl_sim.cpp.
| bool USBLSim::usblBusy |
Definition at line 178 of file usbl_sim.cpp.
| boost::condition_variable USBLSim::usblCondition |
Definition at line 177 of file usbl_sim.cpp.
Definition at line 172 of file usbl_sim.cpp.
Definition at line 172 of file usbl_sim.cpp.
| bool USBLSim::useDevice |
Definition at line 178 of file usbl_sim.cpp.
| auv_msgs::NavSts USBLSim::vehicleState |
Definition at line 174 of file usbl_sim.cpp.
| boost::mutex USBLSim::vehicleStateMux |
Definition at line 176 of file usbl_sim.cpp.