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/PIDController.h>
00037 #include <labust/control/SOIdentification.hpp>
00038 #include <labust_uvapp/VelConConfig.h>
00039 #include <labust_uvapp/ConfigureVelocityController.h>
00040 #include <labust_uvapp/EnableControl.h>
00041 #include <navcon_msgs/ModelParamsUpdate.h>
00042 #include <dynamic_reconfigure/server.h>
00043
00044 #include <auv_msgs/NavSts.h>
00045 #include <auv_msgs/BodyVelocityReq.h>
00046 #include <auv_msgs/BodyForceReq.h>
00047 #include <ros/ros.h>
00048 #include <std_msgs/String.h>
00049 #include <sensor_msgs/Joy.h>
00050
00051 #include <string>
00052 #include <map>
00053
00054 namespace labust
00055 {
00056 namespace control
00057 {
00063 class VelocityControl
00064 {
00065 enum {u=0,v,w,p,q,r};
00066 enum {X=0,Y,Z,K,M,N};
00067 enum {alpha=0,beta,betaa};
00068 enum {Kp=0,Ki,Kd,Kt};
00069 enum {disableAxis=0,
00070 manualAxis=1,
00071 controlAxis=2,
00072 identAxis=3,
00073 directAxis=4};
00074
00075 public:
00079 VelocityControl();
00083 void onInit();
00087 void step();
00091 void start();
00092
00093 private:
00097 void handleReference(const auv_msgs::BodyVelocityReq::ConstPtr& ref);
00101 void handleEstimates(const auv_msgs::NavSts::ConstPtr& estimate);
00105 void handleMeasurement(const auv_msgs::NavSts::ConstPtr& meas);
00109 void handleWindup(const auv_msgs::BodyForceReq::ConstPtr& tau);
00113 void handleModelUpdate(const navcon_msgs::ModelParamsUpdate::ConstPtr& update);
00117 void handleExt(const auv_msgs::BodyForceReq::ConstPtr& tau);
00121 void handleManual(const sensor_msgs::Joy::ConstPtr& joy);
00125 bool handleServerConfig(labust_uvapp::ConfigureVelocityController::Request& req,
00126 labust_uvapp::ConfigureVelocityController::Response& resp);
00130 bool handleEnableControl(labust_uvapp::EnableControl::Request& req,
00131 labust_uvapp::EnableControl::Response& resp);
00135 void dynrec_cb(labust_uvapp::VelConConfig& config, uint32_t level);
00139 void safetyTest();
00143 void updateDynRecConfig();
00147 double doIdentification(int i);
00151 ros::NodeHandle nh,ph;
00155 ros::Time lastRef, lastMan, lastEst, lastMeas;
00159 double timeout;
00160
00164 void initialize_controller();
00168 PIDController controller[r+1];
00172 boost::shared_ptr<SOIdentification> ident[r+1];
00176 double measurement[r+1];
00180 float tauManual[N+1], tauExt[N+1];
00184 double joy_scale, Ts;
00188 boost::array<int32_t,r+1> axis_control;
00192 bool suspend_axis[r+1], externalIdent;
00196 boost::recursive_mutex serverMux;
00197
00201 ros::Publisher tauOut, tauAchW;
00205 ros::Subscriber velocityRef, stateHat, manualIn, tauAch, measSub, identExt, modelUpdate;
00209 ros::ServiceServer highLevelSelect, enableControl;
00213 labust_uvapp::VelConConfig config;
00217 dynamic_reconfigure::Server<labust_uvapp::VelConConfig> server;
00221 const static std::string dofName[r+1];
00222 };
00223 }
00224 }
00225
00226
00227 #endif