Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef CNRRemoteRADIO_HPP_
00038 #define CNRRemoteRADIO_HPP_
00039 #include <cart2/RadioModemConfig.h>
00040
00041 #include <dynamic_reconfigure/server.h>
00042
00043 #include <boost/asio.hpp>
00044 #include <boost/thread/mutex.hpp>
00045 #include <boost/thread.hpp>
00046 #include <boost/archive/binary_oarchive.hpp>
00047
00048 #include <sensor_msgs/Joy.h>
00049 #include <std_msgs/Int32.h>
00050 #include <std_msgs/Bool.h>
00051 #include <geometry_msgs/PointStamped.h>
00052 #include <tf/transform_listener.h>
00053 #include <tf/transform_broadcaster.h>
00054 #include <auv_msgs/NavSts.h>
00055 #include <ros/ros.h>
00056
00057 #include <sstream>
00058
00059 namespace labust
00060 {
00061 namespace control
00062 {
00066 class CNRRemoteRadio
00067 {
00068 enum {sync_length=3, chksum_size = 2};
00069
00070 enum {id_field = 3, data1_field = 4, data2_field=8, mode_field = 12, launch_field=4};
00071 enum {stopbit, startbit, manualbit, automaticbit, remotebit};
00072 enum {cart =0, bart=1, station=2};
00073
00074 enum {latlonmux = 10000000};
00075 public:
00079 CNRRemoteRadio();
00083 ~CNRRemoteRadio();
00087 void onInit();
00091 void start();
00092
00093 private:
00097 void onStateHat(const auv_msgs::NavSts::ConstPtr& estimate);
00101 void onCurrentMode(const std_msgs::Int32::ConstPtr& mode);
00105 void onLaunch(const std_msgs::Bool::ConstPtr& launch);
00109 void start_receive();
00113 void onSync(const boost::system::error_code& error, const size_t& transferred);
00117 void onIncomingData(const boost::system::error_code& error, const size_t& transferred);
00121 void onTimeout();
00125 void reply();
00129 void replyBuoy();
00133 void dummyRequest();
00134
00138 ros::NodeHandle nh,ph;
00142 ros::Time lastModemMsg;
00146 double timeout, currYaw, yawInc, currLat, currLon, desiredHeading, buoyDistance, desiredLat, desiredLon;
00150 ros::Publisher joyOut, launched, hlMsg, posOut, posCOut;
00154 ros::Subscriber extPoint, joyIn, stateHat, stateMeas, curMode, launchFlag;
00158 boost::asio::io_service io;
00162 boost::asio::serial_port port;
00166 boost::thread iorunner;
00170 boost::mutex cdataMux,clientMux;
00174 std::vector<uint8_t> buffer;
00178 uint8_t ringBuffer[sync_length];
00182 ros::ServiceClient client;
00186 int32_t id;
00190 bool doDummyRequest, doLaunch, wasLaunched;
00194 uint8_t lastmode;
00195 };
00196 }
00197 }
00198
00199 #endif