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 #ifndef HEADINGCONTROL_TEST_HPP_
00038 #define HEADINGCONTROL_TEST_HPP_
00039 #include <labust/control/HLControl.hpp>
00040 #include <labust/control/PIDController.h>
00041 #include <labust/math/NumberManipulation.hpp>
00042 #include <std_msgs/Float32.h>
00043
00044 struct HeadingControl
00045 {
00046 HeadingControl():Ts(0.1){};
00047
00048 void init()
00049 {
00050 ros::NodeHandle nh;
00051 headingRef = nh.subscribe<std_msgs::Float32>("heading_ref", 1,
00052 &HeadingControl::onHeadingRef,this);
00053
00054 initialize_controller();
00055 }
00056
00057 void onHeadingRef(const std_msgs::Float32::ConstPtr& ref)
00058 {
00059 headingController.desired = ref->data;
00060 };
00061
00062 void windup(const auv_msgs::BodyForceReq& tauAch)
00063 {
00064
00065 headingController.windup = tauAch.disable_axis.yaw;
00066 };
00067
00068 void step(const auv_msgs::NavSts::ConstPtr& state, auv_msgs::BodyVelocityReqPtr nu)
00069 {
00070
00071
00072 headingController.state = labust::math::wrapRad(state->orientation.yaw);
00073 float errorWrap = labust::math::wrapRad(headingController.desired - headingController.state);
00074 PIFFExtController_stepWrap(&headingController,Ts, errorWrap);
00075
00076 nu->header.stamp = ros::Time::now();
00077 nu->goal.requester = "heading_controller";
00078 nu->twist.angular.z = headingController.output;
00079 }
00080
00081 void initialize_controller()
00082 {
00083 ROS_INFO("Initializing heading controller...");
00084
00085 double w(1);
00086 ros::NodeHandle nh;
00087 nh.param("heading_control/heading_closed_loop_freq", w,w);
00088 nh.param("heading_control/sampling",Ts,Ts);
00089
00090 enum {Kp=0, Ki, Kd, Kt};
00091 PIDController_init(&headingController);
00092 headingController.gains[Kp] = 2*w;
00093 headingController.gains[Ki] = w*w;
00094 headingController.autoTracking = 0;
00095
00096 ROS_INFO("Heading controller initialized.");
00097 }
00098
00099 private:
00100 PIDController headingController;
00101 ros::Subscriber headingRef;
00102 double Ts;
00103 };
00104
00105 #endif
00106
00107
00108