IdentificationNode.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: 30.10.2013.
00036  *********************************************************************/
00037 #include <labust/control/IdentificationNode.hpp>
00038 #include <labust/math/NumberManipulation.hpp>
00039 #include <labust/tools/conversions.hpp>
00040 
00041 #include <auv_msgs/BodyForceReq.h>
00042 
00043 #include <boost/bind.hpp>
00044 
00045 using namespace labust::control;
00046 
00047 const char dofNames[]={'X','Y','Z','K','M','N','A'};
00048 
00049 IdentificationNode::IdentificationNode():
00050                                 measurements(Eigen::Matrix<double,6,1>::Zero()),
00051                                 integrateUV(true)
00052 {
00053         this->onInit();
00054 }
00055 
00056 void IdentificationNode::onInit()
00057 {
00058         ros::NodeHandle nh,ph("~");
00059         aserver.reset(new ActionServer(nh,
00060                         "Identification",
00061                         boost::bind(&IdentificationNode::doIdentification, this, _1),
00062                         false));
00063         aserver->start();
00064 
00065         tauOut = nh.advertise<auv_msgs::BodyForceReq>("tauOut", 1);
00066         meas = nh.subscribe<auv_msgs::NavSts>("meas", 1,
00067                         &IdentificationNode::onMeasurement,this);
00068 
00069         ph.param("integrateUV",integrateUV, true);
00070 }
00071 
00072 void IdentificationNode::onMeasurement(const auv_msgs::NavSts::ConstPtr& meas)
00073 {
00074         static ros::Time lastSampleTime=ros::Time::now();
00075 
00076         if (integrateUV)
00077         {
00078                 boost::mutex::scoped_lock l(measmux);
00079                 double dT = (ros::Time::now() - lastSampleTime).toSec();
00080                 lastSampleTime = ros::Time::now();
00081                 //ROS_INFO("Estimated rate: %f",dT);
00082                 measurements(x) += meas->body_velocity.x*dT;
00083                 measurements(y) += meas->body_velocity.y*dT;
00084                 ROS_INFO("Estimated pos: Ts=%f, x=%f, y=%f",dT, measurements(x), measurements(y));
00085         }
00086         else
00087         {
00088                 boost::mutex::scoped_lock l(measmux);
00089                 measurements(x) = meas->position.north;
00090                 measurements(y) = meas->position.east;
00091         }
00092         measurements(z) = meas->altitude;
00093         measurements(roll) = meas->orientation.roll;
00094         measurements(pitch) = meas->orientation.pitch;
00095         measurements(yaw) = meas->orientation.yaw;
00096 }
00097 
00098 void IdentificationNode::doIdentification(const Goal::ConstPtr& goal)
00099 {
00100         ROS_INFO("Recevied goal.");
00101 
00102         //Some run-time sanity checking.
00103         if ((goal->sampling_rate <= 0) ||
00104                         (goal->command == 0) ||
00105                         (goal->hysteresis == 0) ||
00106                         (goal->dof < 0) || (goal->dof > goal->Yaw))
00107         {
00108                 ROS_ERROR("Some identification criteria are faulty: "
00109                                 "command: (%f != 0), "
00110                                 "hysteresis: (%f != 0), "
00111                                 "dof: (abs(%d) < 6), "
00112                                 "(sampling_rate: (%f >=0)", goal->command,
00113                                 goal->hysteresis, goal->dof, goal->sampling_rate);
00114                 return;
00115         }
00116 
00117         ros::Rate rate(goal->sampling_rate);
00118         int oscnum(0);
00119 
00120         SOIdentification ident;
00121         ident.setRelay(goal->command,goal->hysteresis);
00122         ident.Ref(goal->reference);
00123 
00124         ROS_INFO("Started identification of %c DOF.",dofNames[goal->dof]);
00125 
00126         //Reset the integrals
00127         if (integrateUV)
00128         {
00129                 boost::mutex::scoped_lock l(measmux);
00130                 measurements(x)=0;
00131                 measurements(y)=0;
00132         }
00133 
00134         while (!ident.isFinished())
00135         {
00136                 double error = goal->reference - measurements(goal->dof);
00137                 //Handle angular values
00138                 if (goal->dof >= roll)
00139                 {
00140                         error = labust::math::wrapRad(
00141                                         labust::math::wrapRad(goal->reference) -
00142                                         labust::math::wrapRad(measurements(goal->dof)));
00143                 }
00144                 //Perform one step
00145                 this->setTau(goal->dof, ident.step(error, 1/goal->sampling_rate));
00146 
00147                 //Check for preemption
00148                 if (aserver->isPreemptRequested() || !ros::ok())
00149                 {
00150                         ROS_INFO("DOFIdentification for %d: Preempted", goal->dof);
00151                         //Set output to zero
00152                         this->setTau(goal->dof, 0.0);
00153                         // set the action state to preempted
00154                         aserver->setPreempted();
00155                         return;
00156                 }
00157 
00158                 //Send feedback about progress
00159                 if (ident.hasSwitched())
00160                 {
00161                         navcon_msgs::DOFIdentificationFeedback feedback;
00162                         feedback.dof = goal->dof;
00163                         feedback.error = ident.avgError();
00164                         feedback.oscillation_num = ++oscnum/2;
00165                         aserver->publishFeedback(feedback);
00166                 }
00167 
00168                 //Set the feedback value
00169                 rate.sleep();
00170         }
00171 
00172         //Stop the vessel
00173         this->setTau(goal->dof, 0.0);
00174 
00175         if (ident.isFinished())
00176         {
00177                 const std::vector<double>& params = ident.parameters();
00178                 Result result;
00179                 result.dof = goal->dof;
00180                 result.alpha = params[SOIdentification::alpha];
00181                 result.beta = params[SOIdentification::kx];
00182                 result.betaa = params[SOIdentification::kxx];
00183                 result.delta = params[SOIdentification::delta];
00184                 result.wn = params[SOIdentification::wn];
00185 
00186                 ROS_INFO("Identified parameters: %f %f %f %f",
00187                                 params[SOIdentification::alpha],
00188                                 params[SOIdentification::kx],
00189                                 params[SOIdentification::kxx],
00190                                 params[SOIdentification::delta],
00191                                 params[SOIdentification::wn]);
00192 
00193                 // set the action state to succeeded
00194                 aserver->setSucceeded(result);
00195         }
00196 }
00197 
00198 void IdentificationNode::setTau(int elem, double value)
00199 {
00200         labust::simulation::vector tauvec = labust::simulation::vector::Zero();
00201         tauvec(elem) = value;
00202         std::ostringstream out;
00203         out<<"ident_"<<dofNames[elem];
00204         auv_msgs::BodyForceReqPtr tau(new auv_msgs::BodyForceReq());
00205         tau->header.stamp = ros::Time::now();
00206         tau->goal.requester = out.str();
00207         labust::tools::vectorToPoint(tauvec,tau->wrench.force);
00208         labust::tools::vectorToPoint(tauvec,tau->wrench.torque,3);
00209         tauOut.publish(tau);
00210 }
00211 
00212 int main(int argc, char* argv[])
00213 {
00214         ros::init(argc,argv,"ident_node");
00215         labust::control::IdentificationNode ident;
00216         ros::spin();
00217         return 0;
00218 }


ident_so
Author(s): Gyula Nagy
autogenerated on Mon Oct 6 2014 01:39:47