VirtualTarget.cpp
Go to the documentation of this file.
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/VirtualTarget.hpp>
00038 #include <labust/tools/MatrixLoader.hpp>
00039 #include <labust/tools/conversions.hpp>
00040 
00041 #include <auv_msgs/BodyVelocityReq.h>
00042 #include <geometry_msgs/TransformStamped.h>
00043 #include <boost/bind.hpp>
00044 
00045 #include <cmath>
00046 #include <vector>
00047 #include <string>
00048 
00049 using labust::control::VirtualTarget;
00050 
00051 VirtualTarget::VirtualTarget():
00052                 nh(ros::NodeHandle()),
00053                 ph(ros::NodeHandle("~")),
00054                 lastEst(ros::Time::now()),
00055                 timeout(0.5),
00056                 Ts(0.1),
00057                 safetyRadius(0.5),
00058                 surge(1),
00059                 flowSurgeEstimate(0),
00060                 K1(0.2),
00061                 K2(1),
00062                 gammaARad(45),
00063                 enable(false),
00064                 use_flow_frame(false),
00065                 listener(transBuffer)
00066 {this->onInit();}
00067 
00068 void VirtualTarget::onInit()
00069 {
00070         //Initialize publishers
00071         nuRef = nh.advertise<auv_msgs::BodyVelocityReq>("nuRef", 1);
00072         vtTwist = nh.advertise<geometry_msgs::TwistStamped>("virtual_target_twist", 1);
00073 
00074         //Initialze subscribers
00075         stateHat = nh.subscribe<auv_msgs::NavSts>("stateHat", 1,
00076                         &VirtualTarget::onEstimate,this);
00077         flowTwist = nh.subscribe<geometry_msgs::TwistStamped>("body_flow_frame_twist", 1,
00078                         &VirtualTarget::onFlowTwist,this);
00079         //      refPoint = nh.subscribe<geometry_msgs::PointStamped>("LFPoint", 1,
00080         //                      &VirtualTarget::onNewPoint,this);
00081         //      refTrack = nh.subscribe<auv_msgs::NavSts>("TrackPoint", 1,
00082         //                      &VirtualTarget::onTrackPoint,this);
00083         windup = nh.subscribe<auv_msgs::BodyForceReq>("tauAch", 1,
00084                         &VirtualTarget::onWindup,this);
00085         openLoopSurge = nh.subscribe<std_msgs::Float32>("open_loop_surge", 1,
00086                         &VirtualTarget::onOpenLoopSurge,this);
00087         enableControl = nh.advertiseService("VT_enable",
00088                         &VirtualTarget::onEnableControl, this);
00089 
00090         nh.param("virtual_target/timeout",timeout,timeout);
00091         nh.param("virtual_target/use_flow_frame",use_flow_frame,use_flow_frame);
00092 
00093         //Configure the dynamic reconfigure server
00094         //server.setCallback(boost::bind(&VelocityControl::dynrec_cb, this, _1, _2));
00095 
00096         initialize_controller();
00097         //config.__fromServer__(ph);
00098         //server.setConfigDefault(config);
00099         //this->updateDynRecConfig();
00100 }
00101 
00102 //void VirtualTarget::updateDynRecConfig()
00103 //{
00104 //      ROS_INFO("Updating the dynamic reconfigure parameters.");
00105 //
00106 //      config.__fromServer__(ph);
00107 //      config.Surge_mode = axis_control[u];
00108 //      config.Sway_mode = axis_control[v];
00109 //      config.Heave_mode = axis_control[w];
00110 //      config.Roll_mode = axis_control[p];
00111 //      config.Pitch_mode = axis_control[q];
00112 //      config.Yaw_mode = axis_control[r];
00113 //
00114 //      config.High_level_controller="0 - None\n 1 - DP";
00115 //
00116 //      server.updateConfig(config);
00117 //}
00118 
00119 //void VirtualTarget::dynrec_cb(labust_uvapp::VelConConfig& config, uint32_t level)
00120 //{
00121 //      this->config = config;
00122 //
00123 //      for(size_t i=u; i<=r; ++i)
00124 //      {
00125 //              int newMode(0);
00126 //              ph.getParam(dofName[i]+"_mode", newMode);
00127 //              //Stop the identification if it was aborted remotely.
00128 //              if ((axis_control[i] == identAxis) &&
00129 //                              (newMode != identAxis) &&
00130 //                              (ident[i] != 0)) ident[i].reset();
00131 //
00132 //              axis_control[i] = newMode;
00133 //      }
00134 //}
00135 
00136 //void VirtualTarget::onNewPoint(const geometry_msgs::PointStamped::ConstPtr& point)
00137 //{
00138 //      trackPoint.position.north = point->point.x;
00139 //      trackPoint.position.east = point->point.y;
00140 //      trackPoint.position.depth = point->point.z;
00141 //};
00142 
00143 bool VirtualTarget::onEnableControl(labust_uvapp::EnableControl::Request& req,
00144                 labust_uvapp::EnableControl::Response& resp)
00145 {
00146         this->enable = req.enable;
00147         return true;
00148 }
00149 
00150 void VirtualTarget::onOpenLoopSurge(const std_msgs::Float32::ConstPtr& surge)
00151 {
00152         this->surge = surge->data;
00153 }
00154 
00155 void VirtualTarget::onFlowTwist(const geometry_msgs::TwistStamped::ConstPtr& flowtwist)
00156 {
00157         boost::mutex::scoped_lock l(dataMux);
00158         flowSurgeEstimate = flowtwist->twist.linear.x*flowtwist->twist.linear.x;
00159         flowSurgeEstimate += flowtwist->twist.linear.y*flowtwist->twist.linear.y;
00160         flowSurgeEstimate = sqrt(flowSurgeEstimate);
00161 }
00162 
00163 void VirtualTarget::onEstimate(const auv_msgs::NavSts::ConstPtr& estimate)
00164 {
00165         //Copy into controller
00166         state = *estimate;
00167         lastEst = ros::Time::now();
00168         if (enable) this->step();
00169 };
00170 
00171 //void VirtualTarget::onTrackPoint(const auv_msgs::NavSts::ConstPtr& ref)
00172 //{
00173 //      //Copy into controller
00174 //      trackPoint = *ref;
00175 //};
00176 
00177 void VirtualTarget::onWindup(const auv_msgs::BodyForceReq::ConstPtr& tauAch)
00178 {
00179         //Copy into controller
00180         headingController.windup = tauAch->disable_axis.yaw;
00181 };
00182 
00183 //void VirtualTarget::safetyTest()
00184 //{
00185 //      bool refTimeout = (ros::Time::now() - lastRef).toSec() > timeout;
00186 //      bool estTimeout = (ros::Time::now() - lastEst).toSec() > timeout;
00187 //      bool manTimeout = (ros::Time::now() - lastMan).toSec() > timeout;
00188 //      bool measTimeout = (ros::Time::now() - lastMeas).toSec() > timeout;
00189 //      bool changed = false;
00190 //
00191 //      for (int i=u; i<=r;++i)
00192 //      {
00193 //              bool cntChannel = (refT*imeout || estTimeout) && (axis_control[i] == controlAxis);
00194 //              if (cntChannel) ROS_WARN("Timeout on the control channel. Controlled axes will be disabled.");
00195 //              bool measChannel = measTimeout && (axis_control[i] == identAxis);
00196 //              if (measChannel) ROS_WARN("Timeout on the measurement channel. Stopping identifications in progress.");
00197 //              bool manChannel = manTimeout && (axis_control[i] == manualAxis);
00198 //              if (manChannel) ROS_WARN("Timeout on the manual channel. Manual axes will be disabled.");
00199 //
00200 //              suspend_axis[i] = (cntChannel || measChannel || manChannel);
00201 //      }
00202 //
00203 //      //Update only on change.
00204 //      //if (changed) this->updateDynRecConfig();
00205 //}
00206 
00207 void VirtualTarget::step()
00208 {
00209         if (!enable) return;
00210         //this->safetyTest();
00211 
00212   geometry_msgs::TransformStamped sfTransform, sfLocal, flowLocal;
00213         try
00214         {
00215                 sfTransform = transBuffer.lookupTransform("serret_frenet_frame", "base_link_flow", ros::Time(0));
00216                 flowLocal = transBuffer.lookupTransform("local", "base_link_flow", ros::Time(0));
00217                 sfLocal = transBuffer.lookupTransform("local", "serret_frenet_frame", ros::Time(0));
00218                 double gamma,gammaRabbit,flow_yaw,pitch,roll;
00219                 labust::tools::eulerZYXFromQuaternion(sfTransform.transform.rotation,
00220                                 roll, pitch, gamma);
00221                 labust::tools::eulerZYXFromQuaternion(sfLocal.transform.rotation,
00222                                 roll, pitch, gammaRabbit);
00223                 labust::tools::eulerZYXFromQuaternion(flowLocal.transform.rotation, roll, pitch, flow_yaw);
00224 
00225                 //double UvecYaw = state.orientation.yaw;
00226                 //For slow movements prefer the body frame instead of the flow frame.
00227                 boost::mutex::scoped_lock l(dataMux);
00228                 if (!use_flow_frame || (flowSurgeEstimate < (surge/10)))
00229                 {
00230                         gamma = labust::math::wrapRad(state.orientation.yaw-gammaRabbit);
00231                         flowSurgeEstimate = state.body_velocity.x;
00232                         headingController.state = labust::math::wrapRad(state.orientation.yaw);
00233                 }
00234                 else
00235                 {
00236                         headingController.state = labust::math::wrapRad(flow_yaw);
00237                 }
00238                 l.unlock();
00239 
00240                 gamma=labust::math::wrapRad(gamma);
00241 
00242                 double distance(pow(sfTransform.transform.translation.y,2) + pow(sfTransform.transform.translation.x,2));
00243                 double angleDiff(atan2(sfTransform.transform.translation.y, sfTransform.transform.translation.x));
00244                 if (false && distance > 0.5 && fabs(angleDiff) > M_PI/2)
00245                 {
00246                         headingController.desired = angleDiff;
00247                 }
00248                 else
00249                 {
00250                         //Just for readability
00251                         double s1(sfTransform.transform.translation.x),y1(sfTransform.transform.translation.y);
00252 
00253                         geometry_msgs::TwistStamped sTwist;
00254                         //double flowSurgeEstimate = state.body_velocity.x;
00255                         //sDot
00256                         boost::mutex::scoped_lock l(dataMux);
00257                         sTwist.twist.linear.x = flowSurgeEstimate*cos(gamma) + K1*s1;
00258                         //sTwist.twist.linear.y = flowSurgeEstimate;
00259                         l.unlock();
00260                         vtTwist.publish(sTwist);
00261 
00262                         double gammaRef=-gammaARad*tanh(K2*y1);
00263 
00264                         headingController.desired = labust::math::wrapRad(gammaRabbit+gammaRef);
00265                 }
00266 
00267                 float errorWrap = labust::math::wrapRad(headingController.desired - headingController.state);
00268                 PIFFExtController_stepWrap(&headingController,Ts, errorWrap);
00269 
00270                 auv_msgs::BodyVelocityReq nu;
00271                 nu.header.stamp = ros::Time::now();
00272                 nu.goal.requester = "virtual_target";
00273                 nu.twist.angular.z = headingController.output;
00274                 nu.twist.linear.x = surge;
00275 
00276                 nuRef.publish(nu);
00277         }
00278         catch (tf2::TransformException& ex)
00279         {
00280                 ROS_ERROR("%s",ex.what());
00281         }
00282 }
00283 
00284 void VirtualTarget::start()
00285 {
00286         ros::spin();
00287 }
00288 
00289 void VirtualTarget::initialize_controller()
00290 {
00291         ROS_INFO("Initializing dynamic positioning controller...");
00292 
00293         double w(1);
00294         nh.param("virtual_target/heading_closed_loop_freq", w,w);
00295         nh.param("virtual_target/sampling",Ts,Ts);
00296         nh.param("virtual_target/approach_angle",gammaARad,gammaARad);
00297         nh.param("virtual_target/openLoopSurge",surge,surge);
00298         gammaARad = gammaARad*M_PI/180;
00299         Eigen::Vector2d gains(Eigen::Vector2d::Ones());
00300         labust::tools::getMatrixParam(nh,"virtual_target/outer_loop_gains", gains);
00301         K1 = gains(0);
00302         K2 = gains(1);
00303 
00304         enum {Kp=0, Ki, Kd, Kt};
00305         PIDController_init(&headingController);
00306         headingController.gains[Kp] = 2*w;
00307         headingController.gains[Ki] = w*w;
00308         headingController.autoTracking = 0;
00309 
00310         ROS_INFO("Line following controller initialized.");
00311 }


labust_uvapp
Author(s): Dula Nad
autogenerated on Sun Mar 1 2015 12:12:22