hector_gps_calibration.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2017, Kevin Daun, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_GPS_CALIBRATION_H_
30 #define HECTOR_GPS_CALIBRATION_H_
31 #include <ros/ros.h>
34 #include <tf2/utils.h>
35 #include <geometry_msgs/PoseStamped.h>
36 #include <nav_msgs/Odometry.h>
37 #include <std_msgs/Empty.h>
38 #include "Eigen/Core"
39 
40 
41 
43 {
44 public:
46 
47 private:
48 
49  void navSatCallback(nav_msgs::Odometry msg);
50  void optimizeCallback(std_msgs::Empty msg);
51  void optimize();
52  void publishTF(const ros::WallTimerEvent &unused_timer_event);
53 
54 
58 
59  std::vector< Eigen::Matrix<double, 2, 1> > gps_poses_;
60  std::vector< Eigen::Matrix<double, 2, 1> > world_poses_;
61  std::vector< double > covariances_;
62 
65 
67 
68  std::vector<ros::WallTimer> wall_timers_;
69 
70  std::array<double, 2> translation_;
71  double rotation_;
72 
76 
77 };
78 
79 #endif //HECTOR_GPS_CALIBRATION_H_
ros::Publisher nav_sat_fix_pub_
std::vector< double > covariances_
tf2_ros::TransformListener tf_listener
tf2_ros::TransformBroadcaster tf_broadcaster
std::vector< ros::WallTimer > wall_timers_
void navSatCallback(nav_msgs::Odometry msg)
std::vector< Eigen::Matrix< double, 2, 1 > > world_poses_
GPSCalibration(ros::NodeHandle &nh)
ros::Subscriber optimize_sub_
std::vector< Eigen::Matrix< double, 2, 1 > > gps_poses_
ros::Subscriber nav_sat_sub_
void publishTF(const ros::WallTimerEvent &unused_timer_event)
std::array< double, 2 > translation_
void optimizeCallback(std_msgs::Empty msg)
tf2_ros::Buffer tf_buffer


hector_gps_calibration
Author(s):
autogenerated on Mon Jun 10 2019 13:34:46