gps_conversion.cpp
Go to the documentation of this file.
00001 /*
00002 
00003  Copyright (c) 2012, Markus Achtelik, ASL, ETH Zurich, Switzerland
00004  You can contact the author at <markus dot achtelik at mavt dot ethz dot ch>
00005 
00006  All rights reserved.
00007 
00008  Redistribution and use in source and binary forms, with or without
00009  modification, are permitted provided that the following conditions are met:
00010  * Redistributions of source code must retain the above copyright
00011  notice, this list of conditions and the following disclaimer.
00012  * Redistributions in binary form must reproduce the above copyright
00013  notice, this list of conditions and the following disclaimer in the
00014  documentation and/or other materials provided with the distribution.
00015  * Neither the name of ETHZ-ASL nor the
00016  names of its contributors may be used to endorse or promote products
00017  derived from this software without specific prior written permission.
00018 
00019  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022  DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030  */
00031 
00032 #include "gps_conversion.h"
00033 
00034 #ifdef __APPLE__
00035 template<typename T> void sincos(T ang, T* s, T* c){
00036   __sincos(ang, s, c);
00037 }
00038 #endif
00039 
00040 namespace asctec_hl_gps
00041 {
00042 
00043 GpsConversion::GpsConversion() :
00044   nh_(""), gps_sub_sync_(nh_, "fcu/gps", 1), imu_sub_sync_(nh_, "fcu/imu_custom", 1),
00045       gps_imu_sync_(GpsImuSyncPolicy(10), gps_sub_sync_, imu_sub_sync_), have_reference_(false),
00046       height_offset_(0), set_height_zero_(false), Q_90_DEG(sqrt(2.0) / 2.0, 0, 0, sqrt(2.0) / 2.0)
00047 {
00048   ros::NodeHandle nh;
00049   ros::NodeHandle pnh("~");
00050 
00051   imu_sub_ = nh.subscribe("fcu/imu_custom", 1, &GpsConversion::imuCallback, this);
00052   gps_sub_ = nh.subscribe("fcu/gps", 1, &GpsConversion::gpsCallback, this);
00053   gps_custom_sub_ = nh.subscribe("fcu/gps_custom", 1, &GpsConversion::gpsCustomCallback, this);
00054 
00055   gps_pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped> ("fcu/gps_pose", 1);
00056   gps_position_pub_ = nh_.advertise<asctec_hl_comm::PositionWithCovarianceStamped> ("fcu/gps_position", 1);
00057   gps_custom_pub_ = nh_.advertise<asctec_hl_comm::GpsCustomCartesian> ("fcu/gps_position_custom", 1);
00058   zero_height_srv_ = nh.advertiseService("set_height_zero", &GpsConversion::zeroHeightCb, this);
00059 
00060   pnh.param("use_pressure_height", use_pressure_height_, false);
00061   ROS_INFO_STREAM("using height measurement from "<< (use_pressure_height_?"pressure sensor":"GPS"));
00062 
00063   if (use_pressure_height_)
00064   {
00065     gps_imu_sync_.registerCallback(boost::bind(&GpsConversion::syncCallback, this, _1, _2));
00066     gps_imu_sync_.setInterMessageLowerBound(0, ros::Duration(0.180)); // gps arrives at max with 5 Hz
00067   }
00068 
00069   if (nh.getParam("/gps_ref_latitude", ref_latitude_))
00070   {
00071     if (nh.getParam("/gps_ref_longitude", ref_longitude_))
00072     {
00073       if (nh.getParam("/gps_ref_altitude", ref_altitude_))
00074       {
00075         initReference(ref_latitude_, ref_longitude_, ref_altitude_);
00076         have_reference_ = true;
00077       }
00078     }
00079   }
00080 }
00081 
00082 bool GpsConversion::zeroHeightCb(std_srvs::EmptyRequest & req, std_srvs::EmptyResponse & resp)
00083 {
00084   set_height_zero_ = true;
00085   return true;
00086 }
00087 
00088 void GpsConversion::syncCallback(const sensor_msgs::NavSatFixConstPtr & gps,
00089                                  const asctec_hl_comm::mav_imuConstPtr & imu)
00090 {
00091   if (gps->status.status != sensor_msgs::NavSatStatus::STATUS_FIX)
00092   {
00093     ROS_WARN_STREAM_THROTTLE(1, "No GPS fix");
00094     return;
00095   }
00096 
00097   if (!have_reference_)
00098   {
00099     ROS_WARN_STREAM_THROTTLE(1, "No GPS reference point set, not publishing");
00100     return;
00101   }
00102 
00103   if (set_height_zero_)
00104   {
00105     set_height_zero_ = false;
00106     height_offset_ = imu->height;
00107   }
00108 
00109   if (use_pressure_height_)
00110   {
00111     asctec_hl_comm::PositionWithCovarianceStampedPtr msg(new asctec_hl_comm::PositionWithCovarianceStamped);
00112     msg->header = gps->header;
00113     msg->position = wgs84ToEnu(gps->latitude, gps->longitude, gps->altitude);
00114     msg->position.z = imu->height - height_offset_;
00115 
00116     gps_position_pub_.publish(msg);
00117   }
00118 }
00119 
00120 void GpsConversion::gpsCallback(const sensor_msgs::NavSatFixConstPtr & gps)
00121 {
00122   if (!have_reference_)
00123   {
00124     ROS_WARN_STREAM_THROTTLE(1, "No GPS reference point set, not publishing");
00125     return;
00126   }
00127 
00128   if (gps->status.status == sensor_msgs::NavSatStatus::STATUS_FIX)
00129   {
00130     gps_position_ = wgs84ToEnu(gps->latitude, gps->longitude, gps->altitude);
00131     if (!use_pressure_height_)
00132     {
00133       asctec_hl_comm::PositionWithCovarianceStampedPtr msg(new asctec_hl_comm::PositionWithCovarianceStamped);
00134       msg->header = gps->header;
00135       msg->position = gps_position_;
00136       msg->covariance = gps->position_covariance;
00137       gps_position_pub_.publish(msg);
00138     }
00139   }
00140   else
00141   {
00142     gps_position_.x = gps_position_.y = gps_position_.z = 0;
00143   }
00144 }
00145 
00146 void GpsConversion::gpsCustomCallback(const asctec_hl_comm::GpsCustomConstPtr & gps)
00147 {
00148   if (!have_reference_)
00149   {
00150     ROS_WARN_STREAM_THROTTLE(1, "No GPS reference point set, not publishing");
00151     return;
00152   }
00153 
00154   if (gps->status.status == sensor_msgs::NavSatStatus::STATUS_FIX)
00155   {
00156     geometry_msgs::Point pos = wgs84ToEnu(gps->latitude, gps->longitude, gps->altitude);
00157 
00158     asctec_hl_comm::GpsCustomCartesianPtr msg(new asctec_hl_comm::GpsCustomCartesian);
00159     msg->header = gps->header;
00160     msg->position = pos;
00161     msg->position_covariance = gps->position_covariance;
00162 
00163     // rotate velocity to ENU !
00164     msg->velocity_x = gps->velocity_x;
00165     msg->velocity_y = gps->velocity_y;
00166 
00167     msg->velocity_covariance = gps->velocity_covariance;
00168 
00169     if (use_pressure_height_)
00170     {
00171       msg->position.z = gps->pressure_height - height_offset_;
00172     }
00173     gps_custom_pub_.publish(msg);
00174   }
00175 
00176 }
00177 
00178 void GpsConversion::imuCallback(const asctec_hl_comm::mav_imuConstPtr & imu)
00179 {
00180   if (gps_position_.x == 0 && gps_position_.y == 0 && gps_position_.z == 0)
00181   {
00182     ROS_WARN_STREAM_THROTTLE(1, "No GPS fix");
00183     return;
00184   }
00185 
00186   if (!have_reference_)
00187   {
00188     ROS_WARN_STREAM_THROTTLE(1, "No GPS reference point set, not publishing");
00189     return;
00190   }
00191 
00192   if (set_height_zero_)
00193   {
00194     set_height_zero_ = false;
00195     height_offset_ = imu->height;
00196   }
00197 
00198   if (gps_pose_pub_.getNumSubscribers() > 0)
00199   {
00200     geometry_msgs::PoseWithCovarianceStampedPtr msg(new geometry_msgs::PoseWithCovarianceStamped);
00201 
00202     // magnetic compass is zero when pointing north, need to rotate measurement 90 deg towards east to be consistent with ENU
00203 
00204     Eigen::Quaterniond orientation(imu->orientation.w, imu->orientation.x, imu->orientation.y, imu->orientation.z);
00205     orientation = Q_90_DEG * orientation;
00206     msg->header = imu->header;
00207     msg->pose.pose.orientation.w = orientation.w();
00208     msg->pose.pose.orientation.x = orientation.x();
00209     msg->pose.pose.orientation.y = orientation.y();
00210     msg->pose.pose.orientation.z = orientation.z();
00211     msg->pose.pose.position = gps_position_;
00212     msg->pose.pose.position.z = imu->height - height_offset_;
00213 
00214     gps_pose_pub_.publish(msg);
00215   }
00216 }
00217 
00218 void GpsConversion::initReference(const double & latitude, const double & longitude, const double & altitude)
00219 {
00220   Eigen::Matrix3d R;
00221   double s_long, s_lat, c_long, c_lat;
00222   sincos(latitude * DEG2RAD, &s_lat, &c_lat);
00223   sincos(longitude * DEG2RAD, &s_long, &c_long);
00224 
00225   R(0, 0) = -s_long;
00226   R(0, 1) = c_long;
00227   R(0, 2) = 0;
00228 
00229   R(1, 0) = -s_lat * c_long;
00230   R(1, 1) = -s_lat * s_long;
00231   R(1, 2) = c_lat;
00232 
00233   R(2, 0) = c_lat * c_long;
00234   R(2, 1) = c_lat * s_long;
00235   R(2, 2) = s_lat;
00236 
00237   ecef_ref_orientation_ = Eigen::Quaterniond(R);
00238 
00239   ecef_ref_point_ = wgs84ToEcef(latitude, longitude, altitude);
00240 }
00241 
00242 Eigen::Vector3d GpsConversion::wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude)
00243 {
00244   const double a = 6378137.0; // semi-major axis
00245   const double e_sq = 6.69437999014e-3; // first eccentricity squared
00246 
00247   double s_long, s_lat, c_long, c_lat;
00248   sincos(latitude * DEG2RAD, &s_lat, &c_lat);
00249   sincos(longitude * DEG2RAD, &s_long, &c_long);
00250 
00251   const double N = a / sqrt(1 - e_sq * s_lat * s_lat);
00252 
00253   Eigen::Vector3d ecef;
00254 
00255   ecef[0] = (N + altitude) * c_lat * c_long;
00256   ecef[1] = (N + altitude) * c_lat * s_long;
00257   ecef[2] = (N * (1 - e_sq) + altitude) * s_lat;
00258 
00259   return ecef;
00260 }
00261 
00262 Eigen::Vector3d GpsConversion::ecefToEnu(const Eigen::Vector3d & ecef)
00263 {
00264   return ecef_ref_orientation_ * (ecef - ecef_ref_point_);
00265 }
00266 
00267 geometry_msgs::Point GpsConversion::wgs84ToEnu(const double & latitude, const double & longitude,
00268                                                const double & altitude)
00269 {
00270   geometry_msgs::Point ret;
00271   Eigen::Vector3d tmp;
00272   tmp = ecefToEnu(wgs84ToEcef(latitude, longitude, altitude));
00273   ret.x = tmp[0];
00274   ret.y = tmp[1];
00275   ret.z = tmp[2];
00276 
00277   // debug ...
00278   //  double dbg_x, dbg_y;
00279   //  latlon2xy_dbg(ref_latitude_, ref_longitude_, latitude, longitude, &dbg_x, &dbg_y);
00280   //  ROS_INFO("local metric coordinates: x: %f/%f y: %f/%f", ret.x, dbg_x, ret.y, dbg_y);
00281 
00282   return ret;
00283 }
00284 
00285 geometry_msgs::Point GpsConversion::wgs84ToNwu(const double & latitude, const double & longitude,
00286                                                const double & altitude)
00287 {
00288   geometry_msgs::Point ret;
00289   Eigen::Vector3d tmp;
00290   tmp = ecefToEnu(wgs84ToEcef(latitude, longitude, altitude));
00291   ret.x = tmp[1];
00292   ret.y = -tmp[0];
00293   ret.z = tmp[2];
00294 
00295   // debug ...
00296   //  double dbg_x, dbg_y;
00297   //  latlon2xy_dbg(ref_latitude_, ref_longitude_, latitude, longitude, &dbg_x, &dbg_y);
00298   //  ROS_INFO("local metric coordinates: x: %f/%f y: %f/%f", ret.x, dbg_y, ret.y, -dbg_x);
00299 
00300   return ret;
00301 }
00302 
00303 } // end namespace
00304 


asctec_hl_gps
Author(s): Markus Achtelik
autogenerated on Sun Oct 5 2014 22:20:57