29 #ifndef HECTOR_GPS_CALIBRATION_H_ 30 #define HECTOR_GPS_CALIBRATION_H_ 35 #include <geometry_msgs/PoseStamped.h> 36 #include <nav_msgs/Odometry.h> 37 #include <std_msgs/Empty.h> 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
double min_pose_distance_
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