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 VELOCITYCONTROL_HPP_
00035 #define VELOCITYCONTROL_HPP_
00036 #include <labust/control/PIDBase.h>
00037 #include <navcon_msgs/VelConConfig.h>
00038 #include <navcon_msgs/ConfigureVelocityController.h>
00039 #include <navcon_msgs/EnableControl.h>
00040 #include <navcon_msgs/ModelParamsUpdate.h>
00041 #include <dynamic_reconfigure/server.h>
00042
00043 #include <auv_msgs/NavSts.h>
00044 #include <auv_msgs/BodyVelocityReq.h>
00045 #include <auv_msgs/BodyForceReq.h>
00046 #include <ros/ros.h>
00047 #include <std_msgs/String.h>
00048 #include <sensor_msgs/Joy.h>
00049
00050 #include <string>
00051 #include <map>
00052
00053 namespace labust
00054 {
00055 namespace control
00056 {
00071 class VelocityControl
00072 {
00073 enum {u=0,v,w,p,q,r};
00074 enum {X=0,Y,Z,K,M,N};
00075 enum {alpha=0,beta,betaa};
00076 enum {Kp=0,Ki,Kd,Kt};
00077 enum {disableAxis=0,
00078 manualAxis=1,
00079 controlAxis=2,
00080 identAxis=3,
00081 directAxis=4};
00082 enum {numcnt = 6};
00083
00084 public:
00088 VelocityControl();
00092 void onInit();
00096 void step();
00100 void start();
00101
00102 private:
00106 void handleReference(const auv_msgs::BodyVelocityReq::ConstPtr& ref);
00110 void handleEstimates(const auv_msgs::NavSts::ConstPtr& estimate);
00114 void handleMeasurement(const auv_msgs::NavSts::ConstPtr& meas);
00118 void handleWindup(const auv_msgs::BodyForceReq::ConstPtr& tau);
00122 void handleModelUpdate(const navcon_msgs::ModelParamsUpdate::ConstPtr& update);
00126 void handleExt(const auv_msgs::BodyForceReq::ConstPtr& tau);
00130 void handleManual(const sensor_msgs::Joy::ConstPtr& joy);
00134 bool handleServerConfig(navcon_msgs::ConfigureVelocityController::Request& req,
00135 navcon_msgs::ConfigureVelocityController::Response& resp);
00139 bool handleEnableControl(navcon_msgs::EnableControl::Request& req,
00140 navcon_msgs::EnableControl::Response& resp);
00144 void dynrec_cb(navcon_msgs::VelConConfig& config, uint32_t level);
00148 void safetyTest();
00152 void updateDynRecConfig();
00156 ros::NodeHandle nh,ph;
00160 ros::Time lastRef, lastMan, lastEst, lastMeas;
00164 double timeout;
00165
00169 void initialize_controller();
00173 PIDBase controller[r+1];
00177 double measurement[r+1];
00181 float tauManual[N+1], tauExt[N+1];
00185 double joy_scale, Ts;
00189 boost::array<int32_t,r+1> axis_control;
00193 bool suspend_axis[r+1], externalIdent, use_gvel;
00197 boost::recursive_mutex serverMux;
00198
00202 ros::Publisher tauOut, tauAchW;
00206 ros::Subscriber velocityRef, stateHat, manualIn, tauAch, measSub, identExt, modelUpdate;
00210 ros::ServiceServer highLevelSelect, enableControl;
00214 navcon_msgs::VelConConfig config;
00218 dynamic_reconfigure::Server<navcon_msgs::VelConConfig> server;
00222 const static std::string dofName[r+1];
00226 bool doSafetyTest;
00227 };
00228 }
00229 }
00230
00231
00232 #endif