00001 /* 00002 * Copyright (c) 2015, Charles River Analytics, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions 00007 * are met: 00008 * 00009 * 1. Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * 2. Redistributions in binary form must reproduce the above 00012 * copyright notice, this list of conditions and the following 00013 * disclaimer in the documentation and/or other materials provided 00014 * with the distribution. 00015 * 3. Neither the name of the copyright holder nor the names of its 00016 * contributors may be used to endorse or promote products derived 00017 * from this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00020 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00021 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00022 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00023 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00024 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00025 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00026 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00027 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00028 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00029 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00030 * POSSIBILITY OF SUCH DAMAGE. 00031 */ 00032 00033 #include <ros/ros.h> 00034 00035 #include <nav_msgs/Odometry.h> 00036 #include <sensor_msgs/Imu.h> 00037 #include <sensor_msgs/NavSatFix.h> 00038 00039 #include <tf/transform_datatypes.h> 00040 00041 #include <Eigen/Dense> 00042 00043 namespace RobotLocalization 00044 { 00045 class NavSatTransform 00046 { 00047 public: 00048 00051 NavSatTransform(); 00052 00055 ~NavSatTransform(); 00056 00059 void run(); 00060 00061 private: 00062 00065 bool broadcastUtmTransform_; 00066 00070 double magneticDeclination_; 00071 00074 double utmOdomTfYaw_; 00075 00078 bool hasGps_; 00079 00082 bool hasOdom_; 00083 00086 bool hasImu_; 00087 00090 bool transformGood_; 00091 00097 bool gpsUpdated_; 00098 00104 bool odomUpdated_; 00105 00111 ros::Time gpsUpdateTime_; 00112 00118 ros::Time odomUpdateTime_; 00119 00126 double yawOffset_; 00127 00133 bool zeroAltitude_; 00134 00137 bool publishGps_; 00138 00141 bool useOdometryYaw_; 00142 00147 std::string worldFrameId_; 00148 00151 std::string utmZone_; 00152 00155 tf::Pose latestWorldPose_; 00156 00159 tf::Pose latestUtmPose_; 00160 00163 tf::Quaternion latestOrientation_; 00164 00167 Eigen::MatrixXd latestUtmCovariance_; 00168 00171 Eigen::MatrixXd latestOdomCovariance_; 00172 00175 tf::Transform utmWorldTransform_; 00176 00179 tf::Transform utmWorldTransInverse_; 00180 00183 void odomCallback(const nav_msgs::OdometryConstPtr& msg); 00184 00187 void gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg); 00188 00191 void imuCallback(const sensor_msgs::ImuConstPtr& msg); 00192 00196 void computeTransform(); 00197 00200 bool prepareGpsOdometry(nav_msgs::Odometry &gpsOdom); 00201 00204 bool prepareFilteredGps(sensor_msgs::NavSatFix &filteredGps); 00205 }; 00206 }