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 reset(const auv_msgs::NavSts& ref, const auv_msgs::NavSts& state)
00073 {
00074 con.internalState = 0;
00075 con.lastState = state.orientation.pitch;
00076 };
00077
00078 auv_msgs::BodyVelocityReqPtr step(const auv_msgs::NavSts& ref,
00079 const auv_msgs::NavSts& state)
00080 {
00081 con.desired = ref.orientation.pitch;
00082 con.state = state.orientation.pitch;
00083
00084
00085
00086
00087 if (useIP)
00088 {
00089 IPFF_ffStep(&con, Ts, 0);
00090 ROS_INFO("Current state=%f, desired=%f, windup=%d", con.state, con.desired, con.windup);
00091 }
00092 else
00093 {
00094 PSatD_dStep(&con, Ts, 0);
00095 ROS_INFO("Current state=%f, desired=%f", con.state, con.desired);
00096 }
00097
00098 auv_msgs::BodyVelocityReqPtr nu(new auv_msgs::BodyVelocityReq());
00099 nu->header.stamp = ros::Time::now();
00100 nu->goal.requester = "pitch_controller";
00101 labust::tools::vectorToDisableAxis(disable_axis, nu->disable_axis);
00102
00103 nu->twist.angular.y = con.output;
00104
00105 return nu;
00106 }
00107
00108 void initialize_controller()
00109 {
00110 ROS_INFO("Initializing pitch controller...");
00111
00112 ros::NodeHandle nh;
00113 double closedLoopFreq(1);
00114 nh.param("pitch_controller/closed_loop_freq", closedLoopFreq, closedLoopFreq);
00115 nh.param("pitch_controller/sampling",Ts,Ts);
00116 nh.param("pitch_controller/use_ip",useIP,useIP);
00117
00118 disable_axis[4] = 0;
00119
00120 PIDBase_init(&con);
00121
00122 if (useIP)
00123 {
00124 IPFF_tune(&con, float(closedLoopFreq));
00125 }
00126 else
00127 {
00128 PSatD_tune(&con, float(closedLoopFreq), 0, 1);
00129 con.outputLimit = 1;
00130 }
00131
00132 ROS_INFO("Pitch controller initialized.");
00133 }
00134
00135 private:
00136 ros::Subscriber Pitch_sub;
00137 PIDBase con;
00138 double Ts;
00139 bool useIP;
00140 };
00141 }}
00142
00143 int main(int argc, char* argv[])
00144 {
00145 ros::init(argc,argv,"Pitch_control");
00146
00147 labust::control::HLControl<labust::control::PitchControl,
00148 labust::control::EnableServicePolicy,
00149 labust::control::WindupPolicy<auv_msgs::BodyForceReq> > controller;
00150
00151 ros::spin();
00152
00153 return 0;
00154 }
00155
00156
00157