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/PSatDController.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/Float32.h>
00049 #include <ros/ros.h>
00050
00051 namespace labust
00052 {
00053 namespace control{
00054 struct PitchControl : DisableAxis
00055 {
00056 enum {x=0,y};
00057
00058 PitchControl():Ts(0.1), useIP(false){};
00059
00060 void init()
00061 {
00062 ros::NodeHandle nh;
00063 initialize_controller();
00064 }
00065
00066 void windup(const auv_msgs::BodyForceReq& tauAch)
00067 {
00068
00069 con.windup = tauAch.disable_axis.pitch;
00070 };
00071
00072 void idle(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state,
00073 const auv_msgs::BodyVelocityReq& track)
00074 {
00075
00076 con.desired = ref.orientation.pitch;
00077 con.output = con.internalState = track.twist.angular.y;
00078 con.lastState = con.state = state.orientation.pitch;
00079 con.lastError = con.desired - con.output;
00080 con.track = state.orientation_rate.pitch;
00081 };
00082
00083 void reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00084 {
00085 con.internalState = 0;
00086 con.lastState = state.orientation.pitch;
00087 };
00088
00089 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00090 const auv_msgs::NavSts& state)
00091 {
00092 con.desired = ref.orientation.pitch;
00093 con.state = state.orientation.pitch;
00094 con.track = state.orientation_rate.pitch;
00095
00096
00097
00098
00099 if (useIP)
00100 {
00101 IPFF_ffStep(&con, Ts, 0);
00102 ROS_INFO("Current state=%f, desired=%f, windup=%d", con.state, con.desired, con.windup);
00103 }
00104 else
00105 {
00106 PSatD_dStep(&con, Ts, 0);
00107 ROS_INFO("Current state=%f, desired=%f", con.state, con.desired);
00108 }
00109
00110 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00111 nu->header.stamp = ros::Time::now();
00112 nu->goal.requester = "pitch_controller";
00113 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00114
00115 nu->twist.angular.y = con.output;
00116
00117 return nu;
00118 }
00119
00120 void initialize_controller()
00121 {
00122 ROS_INFO("Initializing pitch controller...");
00123
00124 ros::NodeHandle nh;
00125 double closedLoopFreq(1);
00126 nh.param("pitch_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00127 nh.param("pitch_controller/sampling",Ts,Ts);
00128 nh.param("pitch_controller/use_ip",useIP,useIP);
00129
00130 disable_axis[4] = 0;
00131
00132 PIDBase_init(&con);
00133
00134 if (useIP)
00135 {
00136 IPFF_tune(&con, float(closedLoopFreq));
00137 }
00138 else
00139 {
00140 PSatD_tune(&con, float(closedLoopFreq), 0, 1);
00141 con.outputLimit = 1;
00142 }
00143
00144 ROS_INFO("Pitch controller initialized.");
00145 }
00146
00147 private:
00148 ros::Subscriber Pitch_sub;
00149 PIDBase con;
00150 double Ts;
00151 bool useIP;
00152 };
00153 }}
00154
00155 int main(int argc, char* argv[])
00156 {
00157 ros::init(argc,argv,"Pitch_control");
00158
00159 labust::control::HLControl<labust::control::PitchControl,
00160 labust::control::EnableServicePolicy,
00161 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00162
00163 ros::spin();
00164
00165 return 0;
00166 }
00167
00168
00169