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
00035
00036
00037 #include <labust/control/HLControl.hpp>
00038 #include <labust/control/EnablePolicy.hpp>
00039 #include <labust/control/WindupPolicy.hpp>
00040 #include <labust/control/PIFFController.h>
00041 #include <labust/control/IPFFController.h>
00042 #include <labust/math/NumberManipulation.hpp>
00043 #include <labust/tools/MatrixLoader.hpp>
00044 #include <labust/tools/conversions.hpp>
00045
00046 #include <Eigen/Dense>
00047 #include <auv_msgs/BodyForceReq.h>
00048 #include <std_msgs/Bool.h>
00049 #include <ros/ros.h>
00050
00051 namespace labust
00052 {
00053 namespace control{
00055 struct HDGControl : DisableAxis
00056 {
00057 enum {N=5};
00058
00059 HDGControl():Ts(0.1),yawRefPast(0.0),manRefFlag(false){};
00060
00061 void init()
00062 {
00063 ros::NodeHandle nh;
00064 manRefSub = nh.subscribe<std_msgs::Bool>("manRefHeading",1,&HDGControl::onManRef,this);
00065 initialize_controller();
00066 }
00067
00068 void onManRef(const std_msgs::Bool::ConstPtr& state)
00069 {
00070 manRefFlag = state->data;
00071 }
00072
00073
00074 void windup(const auv_msgs::BodyForceReq& tauAch)
00075 {
00076
00077 con.extWindup = tauAch.windup.yaw;
00078 };
00079
00080
00081 void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00082 const auv_msgs::BodyVelocityReq& track)
00083 {
00084
00085 con.desired = labust::math::wrapRad(state.orientation.yaw);
00086 con.state = unwrap(state.orientation.yaw);
00087 con.track = track.twist.angular.z;
00088
00089 float werror = labust::math::wrapRad(con.desired - con.state);
00090 float wperror = con.b*werror + (con.b-1)*con.state;
00091 PIFF_wffIdle(&con, Ts, werror, wperror, ref.orientation_rate.yaw);
00092 };
00093
00094 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00095 {
00096
00097 };
00098
00099 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00100 const auv_msgs::NavSts& state)
00101 {
00102 double a = 0;
00103
00104
00105 yawRefPast = labust::math::wrapRad((1-a)*ref.orientation.yaw + (a)*yawRefPast);
00106 con.desired = yawRefPast;
00107
00108 con.state = unwrap(state.orientation.yaw);
00109 con.track = state.orientation_rate.yaw;
00110
00111 float werror = labust::math::wrapRad(con.desired - con.state);
00112 float wperror = con.b*werror + (con.b-1)*con.state;
00113
00114 if(manRefFlag)
00115 {
00116 PIFF_wffStep(&con,Ts, werror, wperror, 0*ref.orientation_rate.yaw);
00117
00118
00119 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00120 nu->header.stamp = ros::Time::now();
00121 nu->goal.requester = "hdg_controller";
00122 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00123 nu->twist.angular.z = con.output;
00124 return nu;
00125
00126 }
00127 else
00128 {
00129 con.track = ref.orientation_rate.yaw;
00130
00131 PIFF_wffIdle(&con, Ts, werror, wperror, ref.orientation_rate.yaw);
00132
00133
00134 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00135 nu->header.stamp = ros::Time::now();
00136 nu->goal.requester = "hdg_controller";
00137 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00138
00139 nu->twist.angular.z = ref.orientation_rate.yaw;
00140 return nu;
00141 }
00142 }
00143
00144 void initialize_controller()
00145 {
00146 ROS_INFO("Initializing heading controller...");
00147
00148 ros::NodeHandle nh;
00149 double closedLoopFreq(1);
00150 nh.param("hdg_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00151 nh.param("hdg_controller/sampling",Ts,Ts);
00152 double overshoot(1.5);
00153 nh.param("hdg_controller/overshoot",overshoot,overshoot);
00154
00155 disable_axis[N] = 0;
00156
00157 PIDBase_init(&con);
00158 PIFF_tune(&con, float(closedLoopFreq), overshoot);
00159
00160 ROS_INFO("Heading controller initialized.");
00161 }
00162
00163 private:
00164 PIDBase con;
00165 double Ts;
00166 labust::math::unwrap unwrap;
00167 double yawRefPast;
00168 ros::Subscriber manRefSub;
00169 bool manRefFlag;
00170 };
00171 }}
00172
00173 int main(int argc, char* argv[])
00174 {
00175 ros::init(argc,argv,"hdg_control");
00176
00177 labust::control::HLControl<labust::control::HDGControl,
00178 labust::control::EnableServicePolicy,
00179 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00180 ros::spin();
00181
00182 return 0;
00183 }
00184
00185
00186