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 TOPSIDERADIO_HPP_
00038 #define TOPSIDERADIO_HPP_
00039 #include <labust/preprocessor/mem_serialized_struct.hpp>
00040 #include <labust/tools/StringUtilities.hpp>
00041 #include <cart2/RadioModemConfig.h>
00042 #include <std_msgs/Float32MultiArray.h>
00043 #include <labust/control/crc16.h>
00044
00045 #include <dynamic_reconfigure/server.h>
00046
00047 #include <boost/asio.hpp>
00048 #include <boost/thread/mutex.hpp>
00049 #include <boost/thread.hpp>
00050 #include <boost/archive/binary_oarchive.hpp>
00051
00052 #include <sensor_msgs/Joy.h>
00053 #include <std_msgs/Int32.h>
00054 #include <geometry_msgs/PointStamped.h>
00055 #include <tf/transform_listener.h>
00056 #include <tf/transform_broadcaster.h>
00057 #include <auv_msgs/NavSts.h>
00058 #include <ros/ros.h>
00059
00060 #include <sstream>
00066 PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN((labust)(radio),TopsideModemData,
00067 (int8_t, surgeForce)
00068 (int8_t, torqueForce)
00069 (int32_t, lat)
00070 (int32_t, lon)
00071 (uint8_t, radius)
00072 (uint8_t, surge)
00073 (int8_t, yaw)
00074 (uint8_t, mode)
00075 (uint8_t, launch)
00076 (uint8_t, mode_update))
00077
00078 namespace labust
00079 {
00080 namespace radio
00081 {
00082 typedef boost::array<int16_t,4> stateVec;
00083 typedef boost::array<int16_t,3> measVec;
00084 }
00085 }
00086 BOOST_CLASS_IMPLEMENTATION(labust::radio::stateVec , boost::serialization::primitive_type)
00087 BOOST_CLASS_IMPLEMENTATION(labust::radio::measVec , boost::serialization::primitive_type)
00088
00089 PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN((labust)(radio),CARTModemData,
00090 (int32_t, origin_lat)
00091 (int32_t, origin_lon)
00092 (uint8_t, mode)
00093 (measVec, state_meas)
00094 (stateVec, state_hat)
00095 (measVec, sf_state)
00096 (int16_t, portRPM)
00097 (int16_t, stbdRPM)
00098 (uint8_t, voltage)
00099 (uint8_t, temp))
00100
00101 namespace labust
00102 {
00103 namespace control
00104 {
00112 class TopsideRadio
00113 {
00114 enum {sync_length=2, chksum_size = 2, topside_package_length=16+chksum_size, cart_package_length=35+chksum_size};
00115
00116 enum {x=0,y,psi,u};
00117 public:
00121 TopsideRadio();
00125 ~TopsideRadio();
00129 void onInit();
00133 void start();
00134
00135 private:
00139 void dynrec_cb(cart2::RadioModemConfig& config, uint32_t level);
00143 void onJoy(const sensor_msgs::Joy::ConstPtr& joy);
00147 void onExtPoint(const auv_msgs::NavSts::ConstPtr& isLaunched);
00151 void onStateHat(const auv_msgs::NavSts::ConstPtr& estimate);
00155 void onStateMeas(const auv_msgs::NavSts::ConstPtr& meas);
00156 void onSFMeas(const auv_msgs::NavSts::ConstPtr& meas);
00157 void onCartInfo(const std_msgs::Float32MultiArray::ConstPtr& info);
00161 void onCurrentMode(const std_msgs::Int32::ConstPtr& mode);
00165 void populateDataFromConfig();
00169 void local2LatLon(double x, double y);
00173 void sendCData();
00177 void start_receive();
00181 void onSync(const boost::system::error_code& error, const size_t& transferred);
00185 void onIncomingData(const boost::system::error_code& error, const size_t& transferred);
00189 template <class MsgType>
00190 uint8_t calculateChecksum(MsgType& chdata)
00191 {
00192 std::ostringstream chk;
00193 boost::archive::binary_oarchive chkSer(chk, boost::archive::no_header);
00194 chkSer << chdata;
00195 return labust::tools::getChecksum(
00196 reinterpret_cast<const uint8_t*>(chk.str().data()), chk.str().size());
00197 }
00201 template <class MsgType>
00202 int calculateCRC16(MsgType& chdata)
00203 {
00204 std::ostringstream chk;
00205 boost::archive::binary_oarchive chkSer(chk, boost::archive::no_header);
00206 chkSer << chdata;
00207 return compute_crc16( reinterpret_cast<const char*>(chk.str().data()), chk.str().size());
00208 }
00212 void onTimeout();
00213
00217 ros::NodeHandle nh,ph;
00221 ros::Time lastModemMsg;
00225 double timeout;
00229 ros::Publisher joyOut, launched, hlMsg, stateHatPub, stateMeasPub, info, selectedPoint, selectedNavSts;
00233 ros::Subscriber extPoint, joyIn, stateHat, stateMeas, curMode, sfFrame, cartInfo;
00237 tf::TransformListener listener;
00241 tf::TransformBroadcaster broadcaster;
00245 boost::asio::io_service io;
00249 boost::asio::serial_port port;
00253 boost::thread iorunner;
00257 dynamic_reconfigure::Server<cart2::RadioModemConfig> server;
00261 cart2::RadioModemConfig config;
00265 labust::radio::TopsideModemData data;
00269 labust::radio::CARTModemData cdata;
00273 boost::mutex dataMux, cdataMux,clientMux;
00277 boost::asio::streambuf sbuffer;
00281 std::string ringBuffer;
00285 bool isTopside, twoWayComms;
00289 ros::ServiceClient client;
00293 double originLat, originLon;
00294 uint8_t lastMode;
00295 };
00296 }
00297 }
00298
00299 #endif