hector_gps_calibration.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2017, Kevin Daun, TU Darmstadt
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 are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef HECTOR_GPS_CALIBRATION_H_
00030 #define HECTOR_GPS_CALIBRATION_H_
00031 #include <ros/ros.h>
00032 #include <tf2_ros/transform_listener.h>
00033 #include <tf2_ros/transform_broadcaster.h>
00034 #include <tf2/utils.h>
00035 #include <geometry_msgs/PoseStamped.h>
00036 #include <nav_msgs/Odometry.h>
00037 #include <std_msgs/Empty.h>
00038 #include "Eigen/Core"
00039 
00040 
00041 
00042 class GPSCalibration
00043 {
00044 public:
00045   GPSCalibration(ros::NodeHandle &nh);
00046 
00047 private:
00048 
00049   void navSatCallback(nav_msgs::Odometry msg);
00050   void optimizeCallback(std_msgs::Empty msg);
00051   void optimize();
00052   void publishTF(const ros::WallTimerEvent &unused_timer_event);
00053 
00054 
00055   tf2_ros::Buffer tf_buffer;
00056   tf2_ros::TransformListener tf_listener;
00057   tf2_ros::TransformBroadcaster tf_broadcaster;
00058 
00059   std::vector< Eigen::Matrix<double, 2, 1> > gps_poses_;
00060   std::vector< Eigen::Matrix<double, 2, 1> > world_poses_;
00061   std::vector< double > covariances_;
00062 
00063   ros::Subscriber nav_sat_sub_;
00064   ros::Subscriber optimize_sub_;
00065 
00066   ros::Publisher nav_sat_fix_pub_;
00067 
00068   std::vector<ros::WallTimer> wall_timers_;
00069 
00070   std::array<double, 2> translation_;
00071   double rotation_;
00072 
00073   bool write_debug_file_;
00074   double max_covariance_;
00075   double min_pose_distance_;
00076 
00077 };
00078 
00079 #endif //HECTOR_GPS_CALIBRATION_H_


hector_gps_calibration
Author(s):
autogenerated on Wed May 8 2019 02:32:14