00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, LABUST, UNIZG-FER 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the LABUST nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * Author: Dula Nad 00035 * Created: 03.05.2013. 00036 *********************************************************************/ 00037 #include <labust/control/HeadingControl.hpp> 00038 #include <labust/tools/MatrixLoader.hpp> 00039 00040 #include <auv_msgs/BodyVelocityReq.h> 00041 #include <geometry_msgs/TwistStamped.h> 00042 #include <boost/bind.hpp> 00043 00044 #include <cmath> 00045 #include <vector> 00046 #include <string> 00047 00048 using labust::control::HeadingControl; 00049 00050 HeadingControl::HeadingControl(): 00051 nh(ros::NodeHandle()), 00052 ph(ros::NodeHandle("~")), 00053 lastEst(ros::Time::now()), 00054 timeout(0.5), 00055 Ts(0.1), 00056 safetyRadius(0.5), 00057 surge(1), 00058 flowSurgeEstimate(0), 00059 K1(0.2), 00060 K2(1), 00061 gammaARad(45), 00062 enable(false) 00063 {this->onInit();} 00064 00065 void HeadingControl::onInit() 00066 { 00067 //Initialize publishers 00068 nuRef = nh.advertise<auv_msgs::BodyVelocityReq>("nuRef", 1); 00069 vtTwist = nh.advertise<geometry_msgs::TwistStamped>("virtual_target_twist", 1); 00070 00071 //Initialze subscribers 00072 stateHat = nh.subscribe<auv_msgs::NavSts>("stateHat", 1, 00073 &HeadingControl::onEstimate,this); 00074 // flowTwist = nh.subscribe<geometry_msgs::TwistStamped>("body_flow_frame_twist", 1, 00075 // &HeadingControl::onFlowTwist,this); 00076 headingRef = nh.subscribe<std_msgs::Float32>("heading_ref", 1, 00077 &HeadingControl::onHeadingRef,this); 00078 // refTrack = nh.subscribe<auv_msgs::NavSts>("TrackPoint", 1, 00079 // &HeadingControl::onTrackPoint,this); 00080 windup = nh.subscribe<auv_msgs::BodyForceReq>("tauAch", 1, 00081 &HeadingControl::onWindup,this); 00082 openLoopSurge = nh.subscribe<std_msgs::Float32>("open_loop_surge", 1, 00083 &HeadingControl::onOpenLoopSurge,this); 00084 enableControl = nh.advertiseService("HDG_enable", 00085 &HeadingControl::onEnableControl, this); 00086 00087 nh.param("dp_controller/timeout",timeout,timeout); 00088 00089 //Configure the dynamic reconfigure server 00090 //server.setCallback(boost::bind(&VelocityControl::dynrec_cb, this, _1, _2)); 00091 00092 initialize_controller(); 00093 //config.__fromServer__(ph); 00094 //server.setConfigDefault(config); 00095 //this->updateDynRecConfig(); 00096 } 00097 00098 //void HeadingControl::updateDynRecConfig() 00099 //{ 00100 // ROS_INFO("Updating the dynamic reconfigure parameters."); 00101 // 00102 // config.__fromServer__(ph); 00103 // config.Surge_mode = axis_control[u]; 00104 // config.Sway_mode = axis_control[v]; 00105 // config.Heave_mode = axis_control[w]; 00106 // config.Roll_mode = axis_control[p]; 00107 // config.Pitch_mode = axis_control[q]; 00108 // config.Yaw_mode = axis_control[r]; 00109 // 00110 // config.High_level_controller="0 - None\n 1 - DP"; 00111 // 00112 // server.updateConfig(config); 00113 //} 00114 00115 //void HeadingControl::dynrec_cb(labust_uvapp::VelConConfig& config, uint32_t level) 00116 //{ 00117 // this->config = config; 00118 // 00119 // for(size_t i=u; i<=r; ++i) 00120 // { 00121 // int newMode(0); 00122 // ph.getParam(dofName[i]+"_mode", newMode); 00123 // //Stop the identification if it was aborted remotely. 00124 // if ((axis_control[i] == identAxis) && 00125 // (newMode != identAxis) && 00126 // (ident[i] != 0)) ident[i].reset(); 00127 // 00128 // axis_control[i] = newMode; 00129 // } 00130 //} 00131 00132 void HeadingControl::onHeadingRef(const std_msgs::Float32::ConstPtr& ref) 00133 { 00134 headingController.desired = ref->data; 00135 }; 00136 00137 bool HeadingControl::onEnableControl(labust_uvapp::EnableControl::Request& req, 00138 labust_uvapp::EnableControl::Response& resp) 00139 { 00140 this->enable = req.enable; 00141 return true; 00142 } 00143 00144 void HeadingControl::onOpenLoopSurge(const std_msgs::Float32::ConstPtr& surge) 00145 { 00146 this->surge = surge->data; 00147 } 00148 00149 //void HeadingControl::onFlowTwist(const geometry_msgs::TwistStamped::ConstPtr& flowtwist) 00150 //{ 00151 // boost::mutex::scoped_lock l(dataMux); 00152 // flowSurgeEstimate = flowtwist->twist.linear.x*flowtwist->twist.linear.x; 00153 // flowSurgeEstimate += flowtwist->twist.linear.y*flowtwist->twist.linear.y; 00154 // flowSurgeEstimate = sqrt(flowSurgeEstimate); 00155 //} 00156 00157 void HeadingControl::onEstimate(const auv_msgs::NavSts::ConstPtr& estimate) 00158 { 00159 //Copy into controller 00160 state = *estimate; 00161 lastEst = ros::Time::now(); 00162 if (enable) this->step(); 00163 }; 00164 00165 //void HeadingControl::onTrackPoint(const auv_msgs::NavSts::ConstPtr& ref) 00166 //{ 00167 // //Copy into controller 00168 // trackPoint = *ref; 00169 //}; 00170 00171 void HeadingControl::onWindup(const auv_msgs::BodyForceReq::ConstPtr& tauAch) 00172 { 00173 //Copy into controller 00174 headingController.windup = tauAch->disable_axis.yaw; 00175 }; 00176 00177 //void HeadingControl::safetyTest() 00178 //{ 00179 // bool refTimeout = (ros::Time::now() - lastRef).toSec() > timeout; 00180 // bool estTimeout = (ros::Time::now() - lastEst).toSec() > timeout; 00181 // bool manTimeout = (ros::Time::now() - lastMan).toSec() > timeout; 00182 // bool measTimeout = (ros::Time::now() - lastMeas).toSec() > timeout; 00183 // bool changed = false; 00184 // 00185 // for (int i=u; i<=r;++i) 00186 // { 00187 // bool cntChannel = (refT*imeout || estTimeout) && (axis_control[i] == controlAxis); 00188 // if (cntChannel) ROS_WARN("Timeout on the control channel. Controlled axes will be disabled."); 00189 // bool measChannel = measTimeout && (axis_control[i] == identAxis); 00190 // if (measChannel) ROS_WARN("Timeout on the measurement channel. Stopping identifications in progress."); 00191 // bool manChannel = manTimeout && (axis_control[i] == manualAxis); 00192 // if (manChannel) ROS_WARN("Timeout on the manual channel. Manual axes will be disabled."); 00193 // 00194 // suspend_axis[i] = (cntChannel || measChannel || manChannel); 00195 // } 00196 // 00197 // //Update only on change. 00198 // //if (changed) this->updateDynRecConfig(); 00199 //} 00200 00201 void HeadingControl::step() 00202 { 00203 if (!enable) return; 00204 //this->safetyTest(); 00205 00206 headingController.state = labust::math::wrapRad(state.orientation.yaw); 00207 float errorWrap = labust::math::wrapRad(headingController.desired - headingController.state); 00208 PIFFExtController_stepWrap(&headingController,Ts, errorWrap); 00209 00210 auv_msgs::BodyVelocityReq nu; 00211 nu.header.stamp = ros::Time::now(); 00212 nu.goal.requester = "heading_controller"; 00213 nu.twist.angular.z = headingController.output; 00214 nu.twist.linear.x = surge; 00215 00216 nuRef.publish(nu); 00217 } 00218 00219 void HeadingControl::start() 00220 { 00221 ros::spin(); 00222 } 00223 00224 void HeadingControl::initialize_controller() 00225 { 00226 ROS_INFO("Initializing heading controller..."); 00227 00228 double w(1); 00229 nh.param("heading_control/heading_closed_loop_freq", w,w); 00230 nh.param("heading_control/sampling",Ts,Ts); 00231 nh.param("heading_control/openLoopSurge",surge,surge); 00232 00233 enum {Kp=0, Ki, Kd, Kt}; 00234 PIDController_init(&headingController); 00235 headingController.gains[Kp] = 2*w; 00236 headingController.gains[Ki] = w*w; 00237 headingController.autoTracking = 0; 00238 00239 ROS_INFO("Heading controller initialized."); 00240 }