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


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:33