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 #ifndef PLADYPOSNODE_HPP_
00035 #define PLADYPOSNODE_HPP_
00036 #include <labust/vehicles/ScaleAllocation.hpp>
00037 #include <pladypos/ThrusterMappingConfig.h>
00038
00039 #include <auv_msgs/BodyForceReq.h>
00040 #include <dynamic_reconfigure/server.h>
00041 #include <ros/ros.h>
00042
00043 #include <Eigen/Dense>
00044
00045 #include <boost/asio.hpp>
00046 #include <boost/thread.hpp>
00047
00048 namespace labust
00049 {
00050 namespace vehicles
00051 {
00058 class PlaDyPosNode
00059 {
00063 static const float sscale[6];
00067 enum {current0, current1, current2, current3, currentConv, voltage};
00068 public:
00072 PlaDyPosNode();
00073
00077 ~PlaDyPosNode();
00078
00079 void configure(ros::NodeHandle& nh, ros::NodeHandle& ph);
00080
00081 protected:
00085 ros::Subscriber tau;
00089 ros::Publisher tauAch, diag, info;
00090
00094 void driverMsg(const int n[4]);
00098 void pubDiagnostics();
00099
00103 void onTau(const auv_msgs::BodyForceReq::ConstPtr tau);
00107 void safetyTest();
00111 void dynrec(pladypos::ThrusterMappingConfig& config, uint32_t level);
00115 void onReply(const boost::system::error_code& error, const size_t& transferred);
00119 void start_receive();
00123 boost::thread safety;
00127 boost::mutex serialMux;
00131 ros::Time lastTau;
00135 double timeout;
00136
00140 dynamic_reconfigure::Server<pladypos::ThrusterMappingConfig> server;
00144 bool revControl;
00145
00149 boost::asio::io_service io;
00153 boost::asio::serial_port port;
00157 boost::thread iorunner;
00161 boost::asio::streambuf sbuffer;
00165 boost::array<float,6> sensors;
00169 int lastRevs[4];
00170
00174 Eigen::Matrix<float, 3,4> B;
00178 ScaleAllocation allocator;
00179 };
00180 }
00181 }
00182
00183 #endif