nav_node.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: 26.03.2013.
00036  *********************************************************************/
00037 #include <labust/navigation/KFCore.hpp>
00038 #include <labust/navigation/XYModel.hpp>
00039 #include <labust/math/uBlasOperations.hpp>
00040 #include <labust/math/NumberManipulation.hpp>
00041 #include <labust/tools/GeoUtilities.hpp>
00042 #include <labust/tools/MatrixLoader.hpp>
00043 #include <labust/tools/conversions.hpp>
00044 #include <labust/tools/DynamicsLoader.hpp>
00045 #include <labust/simulation/DynamicsParams.hpp>
00046 
00047 #include <kdl/frames.hpp>
00048 #include <auv_msgs/NavSts.h>
00049 #include <auv_msgs/BodyForceReq.h>
00050 #include <sensor_msgs/NavSatFix.h>
00051 #include <sensor_msgs/Imu.h>
00052 
00053 #include <tf/transform_broadcaster.h>
00054 #include <tf/transform_listener.h>
00055 
00056 #include <ros/ros.h>
00057 
00058 #include <boost/bind.hpp>
00059 #include <sstream>
00060 #include <fstream>
00061 
00062 typedef labust::navigation::KFCore<labust::navigation::XYModel> KFNav;
00063 tf::TransformListener* listener;
00064 
00065 ros::Time t;
00066 KFNav::vector measurement(KFNav::zeros(KFNav::stateNum)), newMeas(KFNav::zeros(KFNav::stateNum));
00067 
00068 void handleTau(KFNav::vector& tauIn, const auv_msgs::BodyForceReq::ConstPtr& tau)
00069 {
00070         tauIn(KFNav::X) = tau->wrench.force.x;
00071         tauIn(KFNav::Y) = tau->wrench.force.y;
00072         tauIn(KFNav::N) = tau->wrench.torque.z;
00073 };
00074 
00075 void handleGPS(KFNav::vector& xy, const sensor_msgs::NavSatFix::ConstPtr& data)
00076 {
00077         enum {x,y,newMsg};
00078         //Calculate to X-Y tangent plane
00079         tf::StampedTransform transformDeg, transformLocal;
00080         try
00081         {
00082                 listener->lookupTransform("local", "gps_frame", ros::Time(0), transformLocal);
00083                 listener->lookupTransform("/worldLatLon", "local", ros::Time(0), transformDeg);
00084 
00085                 std::pair<double,double> posxy =
00086                                 labust::tools::deg2meter(data->latitude - transformDeg.getOrigin().y(),
00087                                                 data->longitude - transformDeg.getOrigin().x(),
00088                                                 transformDeg.getOrigin().y());
00089 
00090                 //correct for lever arm shift during pitch and roll
00091                 tf::Vector3 pos = tf::Vector3(posxy.first, posxy.second,0);
00092 
00093                 //xy(x) = pos.x();
00094                 //xy(y) = pos.y();
00095                 xy(x) = posxy.first;
00096                 xy(y) = posxy.second;
00097                 xy(newMsg) = 1;
00098 
00099                 //For generic updates
00100                 newMeas(KFNav::xp) = 1;
00101                 newMeas(KFNav::yp) = 1;
00102                 measurement(KFNav::xp) = posxy.first;
00103                 measurement(KFNav::yp) = posxy.second;
00104         }
00105         catch(tf::TransformException& ex)
00106         {
00107                 ROS_ERROR("%s",ex.what());
00108         }
00109 };
00110 
00111 void handleImu(KFNav::vector& rpy, const sensor_msgs::Imu::ConstPtr& data)
00112 {
00113         enum {r,p,y,newMsg};
00114         double roll,pitch,yaw;
00115         static labust::math::unwrap unwrap;
00116         
00117 
00118         tf::StampedTransform transform;
00119         try
00120         {
00121                 t = data->header.stamp;
00122                 listener->lookupTransform("base_link", "imu_frame", ros::Time(0), transform);
00123                 tf::Quaternion meas(data->orientation.x,data->orientation.y,
00124                                 data->orientation.z,data->orientation.w);
00125                 tf::Quaternion result = meas*transform.getRotation();
00126 
00127                 KDL::Rotation::Quaternion(result.x(),result.y(),result.z(),result.w()).GetEulerZYX(yaw,pitch,roll);
00128                 /*labust::tools::eulerZYXFromQuaternion(
00129                                 Eigen::Quaternion<float>(result.x(),result.y(),
00130                                                 result.z(),result.w()),
00131                                 roll,pitch,yaw);*/
00132                 //ROS_INFO("Received RPY:%f,%f,%f",roll,pitch,yaw);
00133 
00134                 rpy(r) = roll;
00135                 rpy(p) = pitch;
00136                 rpy(y) = yaw;
00137                 rpy[newMsg] = 1;
00138 
00139                 //For generic updates
00140                 newMeas(KFNav::psi) = 1;
00141                 newMeas(KFNav::r) = 1;
00142                 measurement(KFNav::psi) = unwrap(yaw);
00143                 measurement(KFNav::r) = data->angular_velocity.z;
00144         }
00145         catch (tf::TransformException& ex)
00146         {
00147                 ROS_ERROR("%s",ex.what());
00148         }
00149 };
00150 
00151 void configureNav(KFNav& nav, ros::NodeHandle& nh)
00152 {
00153         ROS_INFO("Configure navigation.");
00154 
00155         labust::simulation::DynamicsParams params;
00156         labust::tools::loadDynamicsParams(nh, params);
00157 
00158         ROS_INFO("Loaded dynamics params.");
00159 
00160         KFNav::ModelParams surge,sway,yaw;
00161         surge.alpha = params.m + params.Ma(0,0);
00162         sway.alpha = params.m + params.Ma(1,1);
00163         yaw.alpha = params.Io(2,2) + params.Ma(5,5);
00164         surge.beta = params.Dlin(0,0);
00165         sway.beta = params.Dlin(1,1);
00166         yaw.beta = params.Dlin(5,5);
00167         surge.betaa = params.Dquad(0,0);
00168         sway.betaa = params.Dquad(1,1);
00169         yaw.betaa = params.Dquad(5,5);
00170 
00171         std::string sQ,sW,sV,sR,sP,sx0;
00172         nh.getParam("ekfnav/Q", sQ);
00173         nh.getParam("ekfnav/W", sW);
00174         nh.getParam("ekfnav/V", sV);
00175         nh.getParam("ekfnav/R", sR);
00176         nh.getParam("ekfnav/P", sP);
00177         nh.getParam("ekfnav/x0", sx0);
00178         KFNav::matrix Q,W,V,R,P;
00179         KFNav::vector x0;
00180         boost::numeric::ublas::matrixFromString(sQ,Q);
00181         boost::numeric::ublas::matrixFromString(sW,W);
00182         boost::numeric::ublas::matrixFromString(sV,V);
00183         boost::numeric::ublas::matrixFromString(sR,R);
00184         boost::numeric::ublas::matrixFromString(sP,P);
00185         std::stringstream ss(sx0);
00186         boost::numeric::ublas::operator >>(ss,x0);
00187 
00188         double dT(0.1);
00189         nh.param("sampling_time",dT,dT);
00190         nav.setTs(dT);
00191         nav.setParameters(surge,sway,yaw);
00192         nav.setStateParameters(W,Q);
00193         nav.setMeasurementParameters(V,R);
00194         nav.setStateCovariance(P);
00195         nav.initModel();
00196         nav.setState(x0);
00197 }
00198 
00199 void offline_sim(const std::string& filename, KFNav& ekf)
00200 {
00201         std::fstream file(filename.c_str());
00202         std::ofstream log("test.csv");
00203         std::cout<<"Reading log file:"<<filename<<std::endl;
00204 
00205         //Define a desired structure
00206         log<<"%element: off_data\n"
00207         "% body_velocity.x\n"
00208         "% body_velocity.y\n"
00209         "% orientation_rate.yaw\n"
00210         "% position.north\n"
00211         "% position.east\n"
00212         "% orientation.yaw\n"
00213         "% current.xc\n"
00214         "% current.yc\n"
00215         "% b1\n"
00216         "% b2\n"
00217         "%element: off_cov \n"
00218   "% u_cov\n"
00219         "% v_cov\n"
00220         "% r_cov\n"
00221         "% x_cov\n"
00222         "% y_cov\n"
00223         "% psi_cov\n"
00224         "% xc_cov\n"
00225         "% yc_cov\n"
00226         "% b1_cov\n"
00227         "% b2_cov\n";
00228 
00229         double tauX,tauY,tauN,x,y,psi,yaw_rate;
00230         file>>tauX>>tauY>>tauN>>x>>y>>psi>>yaw_rate;
00231 
00232         KFNav::vector state(KFNav::zeros(KFNav::stateNum));
00233         state(KFNav::xp) = x;
00234         state(KFNav::yp) = y;
00235         state(KFNav::psi) = psi;
00236 
00237         ekf.setState(state);
00238 
00239         double lastx,lasty;
00240         labust::math::unwrap unwrap;
00241 
00242         int i=0;
00243         while(!file.eof() && ros::ok())
00244         {
00245                 file>>tauX>>tauY>>tauN>>x>>y>>psi>>yaw_rate;
00246                 //psi -= 2*M_PI*3.0/180;
00247                 KFNav::input_type input(KFNav::inputSize);
00248                 input(KFNav::X) = tauX;
00249                 input(KFNav::Y) = tauY;
00250                 input(KFNav::N) = tauN;
00251                 ekf.predict(input);
00252 
00253                 KFNav::vector newMeas(KFNav::zeros(KFNav::stateNum));
00254                 KFNav::vector measurement(KFNav::zeros(KFNav::stateNum));
00255 
00256                 double yaw = unwrap(psi);
00257 
00258                 newMeas(KFNav::psi) = 1;
00259                 newMeas(KFNav::r) = 1;
00260                 measurement(KFNav::psi) = yaw;
00261                 measurement(KFNav::r) = yaw_rate;
00262 
00263                 if (i%10 == 0)
00264                 {
00265                         //if (!((lastx == x) && (lasty == y)))
00266                         newMeas(KFNav::xp) = 1;
00267                         newMeas(KFNav::yp) = 1;
00268                         measurement(KFNav::xp) = x;
00269                         measurement(KFNav::yp) = y;
00270                 }
00271 
00272                 ekf.correct(ekf.update(measurement, newMeas));
00273 
00274                 lastx=x;
00275                 lasty=y;
00276 
00277                 //std::cout<<"Meas:"<<x<<","<<y<<","<<M_PI*psi/180<<std::endl;
00278                 //std::cout<<"Estimate:"<<ekf.getState()(KFNav::xp)<<",";
00279                 //std::cout<<ekf.getState()(KFNav::yp)<<","<<ekf.getState()(KFNav::psi)<<std::endl;
00280                 //std::cout<<ekf.traceP()<<std::endl;
00281 
00282                 log<<ekf.getState()(0);
00283                 for (size_t j = 1; j< ekf.getState().size(); ++j)
00284                         log<<","<<((j==KFNav::psi)?labust::math::wrapRad(ekf.getState()(j)):ekf.getState()(j));
00285                 for (size_t j = 0; j< ekf.getState().size(); ++j)       log<<","<<ekf.getStateCovariance()(j,j);
00286                 log<<"\n";
00287 
00288                 ++i;
00289         }
00290 }
00291 
00292 //consider making 2 corrections based on arrived measurements (async)
00293 int main(int argc, char* argv[])
00294 {
00295         ros::init(argc,argv,"pladypos_nav");
00296         ros::NodeHandle nh;
00297         KFNav nav;
00298         //Configure the navigation
00299         configureNav(nav,nh);
00300 
00301         double outlierR;
00302         nh.param("outlier_radius",outlierR,1.0);
00303 
00305         //ADDED FOR LOG-BASED NAVIGATION TUNING
00306         bool offline(false);
00307         nh.param("offline",offline,false);
00308         std::string filename("");
00309         nh.param("offline_file",filename,filename);
00310 
00311         if (offline)
00312         {
00313                 offline_sim(filename, nav);
00314                 return 0;
00315         }
00317 
00318         //Publishers
00319         ros::Publisher stateHat = nh.advertise<auv_msgs::NavSts>("stateHat",1);
00320         ros::Publisher stateMeas = nh.advertise<auv_msgs::NavSts>("meas",1);
00321         ros::Publisher currentTwist = nh.advertise<geometry_msgs::TwistStamped>("currentsHat",1);
00322         ros::Publisher bodyFlowFrame = nh.advertise<geometry_msgs::TwistStamped>("body_flow_frame_twist",1);
00323         //Subscribers
00324         KFNav::vector tau(KFNav::zeros(KFNav::inputSize)),xy(KFNav::zeros(2+1)),rpy(KFNav::zeros(3+1));
00325 
00326         tf::TransformBroadcaster broadcast;
00327         listener = new tf::TransformListener();
00328 
00329         ros::Subscriber tauAch = nh.subscribe<auv_msgs::BodyForceReq>("tauAch", 1, boost::bind(&handleTau,boost::ref(tau),_1));
00330         ros::Subscriber navFix = nh.subscribe<sensor_msgs::NavSatFix>("gps", 1, boost::bind(&handleGPS,boost::ref(xy),_1));
00331         ros::Subscriber imu = nh.subscribe<sensor_msgs::Imu>("imu", 1, boost::bind(&handleImu,boost::ref(rpy),_1));
00332 
00333         ros::Rate rate(10);
00334 
00335         auv_msgs::NavSts meas,state;
00336         geometry_msgs::TwistStamped current, flowspeed;
00337         meas.header.frame_id = "local";
00338         state.header.frame_id = "local";
00339         current.header.frame_id = "local";
00340 
00341         labust::math::unwrap unwrap;
00342 
00343         while (ros::ok())
00344         {
00345                 nav.predict(tau);
00346 
00347                 bool newArrived(false);
00348 
00349                 for(size_t i=0; i<newMeas.size(); ++i)
00350                 {
00351                         if ((newArrived = newMeas(i))) break;
00352                 }
00353 
00354                 if (newArrived)
00355                 {
00356                         //Generic measurment outlier rejection
00357                         bool outlier = false;
00358                         double x(nav.getState()(KFNav::xp)), y(nav.getState()(KFNav::yp));
00359                         double inx(0),iny(0);
00360                         nav.calculateXYInovationVariance(nav.getStateCovariance(),inx,iny);
00361                         outlier = sqrt(pow(x-xy(0),2) + pow(y-xy(1),2)) > outlierR*sqrt(inx*inx + iny*iny);
00362                         if (outlier)
00363                         {
00364                                 ROS_INFO("Outlier rejected: meas(%f, %f), estimate(%f,%f), inovationCov(%f,%f)",xy(0),xy(1),x,y,inx,iny);
00365                                 newMeas(KFNav::xp) = 0;
00366                                 newMeas(KFNav::yp) = 0;
00367                         }
00368 
00369                         nav.correct(nav.update(measurement, newMeas));
00370                         //Clear measurements
00371                         newMeas = KFNav::zeros(KFNav::stateNum);
00372                 }
00373 
00374 //              if (rpy(3))
00375 //              {
00376 //                      double yaw = unwrap(rpy(2));
00377 //
00378 //                      bool outlier = false;
00379 //                      double x(nav.getState()(KFNav::xp)), y(nav.getState()(KFNav::yp));
00380 //                      double inx(0),iny(0);
00381 //                      nav.calculateXYInovationVariance(nav.getStateCovariance(),inx,iny);
00382 //                      outlier = sqrt(pow(x-xy(0),2) + pow(y-xy(1),2)) > outlierR*sqrt(inx*inx + iny*iny);
00383 //                      if (outlier)
00384 //                      {
00385 //                              ROS_INFO("Outlier rejected: meas(%f, %f), estimate(%f,%f), inovationCov(%f,%f)",xy(0),xy(1),x,y,inx,iny);
00386 //                              xy(2) = 0;
00387 //                      }
00388 //
00389 //                      if (xy(2) == 1 && !outlier)
00390 //                      {
00391 //                              ROS_INFO("XY correction: meas(%f, %f), estimate(%f,%f), inovationCov(%f,%f,%d)",xy(0),xy(1),x,y,inx,iny,nav.getInovationCovariance().size1());
00392 //                              nav.correct(nav.fullUpdate(xy(0),xy(1),yaw));
00393 //                              xy(2) = 0;
00394 //                      }
00395 //                      else
00396 //                      {
00397 //                              ROS_INFO("Heading correction:%f",yaw);
00398 //                              nav.correct(nav.yawUpdate(yaw));
00399 //                      }
00400 //                      rpy(3) = 0;
00401 //              }
00402 
00403                 meas.orientation.roll = rpy(0);
00404                 meas.orientation.pitch = rpy(1);
00405                 meas.orientation.yaw = rpy(2);
00406                 meas.orientation_rate.yaw = measurement(KFNav::r);
00407                 meas.position.north = xy(0);
00408                 meas.position.east = xy(1);
00409                 meas.header.stamp = ros::Time::now();
00410                 stateMeas.publish(meas);
00411 
00412                 const KFNav::vector& estimate = nav.getState();
00413                 state.body_velocity.x = estimate(KFNav::u);
00414                 state.body_velocity.y = estimate(KFNav::v);
00415                 state.orientation_rate.yaw = estimate(KFNav::r);
00416                 state.position.north = estimate(KFNav::xp);
00417                 state.position.east = estimate(KFNav::yp);
00418                 current.twist.linear.x = estimate(KFNav::xc);
00419                 current.twist.linear.y = estimate(KFNav::yc);
00420 
00421                 const KFNav::matrix& covariance = nav.getStateCovariance();
00422                 state.position_variance.north = covariance(KFNav::xp, KFNav::xp);
00423                 state.position_variance.east = covariance(KFNav::yp, KFNav::yp);
00424                 state.orientation_variance.yaw =  covariance(KFNav::psi, KFNav::psi);
00425 
00426                 try
00427                 {
00428                         tf::StampedTransform transformDeg;
00429                         listener->lookupTransform("/worldLatLon", "local", ros::Time(0), transformDeg);
00430 
00431                         std::pair<double, double> diffAngle = labust::tools::meter2deg(state.position.north,
00432                                         state.position.east,
00433                                         //The latitude angle
00434                                         transformDeg.getOrigin().y());
00435                         state.global_position.latitude = transformDeg.getOrigin().y() + diffAngle.first;
00436                         state.global_position.longitude = transformDeg.getOrigin().x() + diffAngle.second;
00437                         state.origin.latitude = transformDeg.getOrigin().y();
00438                         state.origin.longitude = transformDeg.getOrigin().x();
00439                 }
00440                 catch(tf::TransformException& ex)
00441                 {
00442                         ROS_ERROR("%s",ex.what());
00443                 }
00444 
00445                 state.orientation.yaw = labust::math::wrapRad(estimate(KFNav::psi));
00446 
00447                 tf::StampedTransform transform;
00448                 transform.setOrigin(tf::Vector3(estimate(KFNav::xp), estimate(KFNav::yp), 0.0));
00449                 Eigen::Quaternion<float> q;
00450                 labust::tools::quaternionFromEulerZYX(rpy(0),rpy(1),estimate(KFNav::psi),q);
00451                 transform.setRotation(tf::Quaternion(q.x(),q.y(),q.z(),q.w()));
00452                 broadcast.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "local", "base_link"));
00453 
00454                 //Calculate the flow frame (instead of heading use course)
00455                 double xdot,ydot;
00456                 nav.getNEDSpeed(xdot,ydot);
00457                 labust::tools::quaternionFromEulerZYX(rpy(0),rpy(1),atan2(ydot,xdot),q);
00458                 transform.setRotation(tf::Quaternion(q.x(),q.y(),q.z(),q.w()));
00459                 broadcast.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "local", "base_link_flow"));
00460 
00461                 flowspeed.twist.linear.x = xdot;
00462                 flowspeed.twist.linear.y = ydot;
00463                 bodyFlowFrame.publish(flowspeed);
00464                 currentTwist.publish(current);
00465                 state.header.stamp = t;
00466                 stateHat.publish(state);
00467 
00468                 rate.sleep();
00469                 ros::spinOnce();
00470         }
00471 
00472         return 0;
00473 }
00474 


pladypos
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:37:13