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 LABUST_CONTROL_MANUAL_CONTROL_H
00035 #define LABUST_CONTROL_MANUAL_CONTROL_H
00036
00037 #include <navcon_msgs/ManualConfigure.h>
00038 #include <navcon_msgs/ManualSelect.h>
00039 #include <navcon_msgs/ManualConfiguration.h>
00040 #include <auv_msgs/NavSts.h>
00041 #include <sensor_msgs/Joy.h>
00042 #include <ros/ros.h>
00043
00044 #include <boost/thread/mutex.hpp>
00045
00046 #include <string>
00047 #include <map>
00048
00049 namespace labust
00050 {
00051 namespace control
00052 {
00065 class ManualControl
00066 {
00067 enum {X=0,Y,Z,K,M,N,DOF=6,A=6};
00068
00069 typedef boost::array<int,DOF> GenArray;
00070 typedef std::vector<double> DataType;
00071 typedef navcon_msgs::ManualConfigure::Request CRequest;
00072 typedef navcon_msgs::ManualConfigure::Response CResponse;
00073 typedef navcon_msgs::ManualSelect::Request SRequest;
00074 typedef navcon_msgs::ManualSelect::Response SResponse;
00075
00076 public:
00078 ManualControl();
00079
00081 void onInit();
00082
00083 private:
00085 void onJoystick(const sensor_msgs::Joy::ConstPtr& joy);
00087 void onNavSts(const auv_msgs::NavSts::ConstPtr& nav);
00089 bool onConfiguration(CRequest& req, CResponse& resp);
00091 bool onSelect(SRequest& req, SResponse& resp);
00092
00094 bool setupConfig();
00096 void setDefaultConfig();
00098 void remap(const sensor_msgs::Joy::ConstPtr& joy);
00100 void pubTau(const DataType& tauv);
00102 void pubNu(const DataType& nuv);
00104 void pubEta(const DataType& etaff);
00105
00107 ros::Publisher tauref;
00109 ros::Publisher nuref;
00111 ros::Publisher etaref;
00113 ros::Subscriber joyin;
00115 ros::Subscriber navsts;
00117 ros::ServiceServer config_server;
00119 ros::ServiceServer select_server;
00120
00122 navcon_msgs::ManualConfiguration config;
00124 GenArray generators;
00126 DataType mapped;
00128 boost::mutex cfg_mutex;
00129
00131 DataType navstate;
00133 bool nav_valid;
00135 boost::mutex nav_mutex;
00136 };
00137 }
00138 }
00139
00140
00141 #endif