#include <hector_gps_calibration.h>
Public Member Functions | |
GPSCalibration (ros::NodeHandle &nh) | |
Private Member Functions | |
void | navSatCallback (nav_msgs::Odometry msg) |
void | optimize () |
void | optimizeCallback (std_msgs::Empty msg) |
void | publishTF (const ros::WallTimerEvent &unused_timer_event) |
Private Attributes | |
std::vector< double > | covariances_ |
std::vector< Eigen::Matrix< double, 2, 1 > > | gps_poses_ |
double | max_covariance_ |
double | min_pose_distance_ |
ros::Publisher | nav_sat_fix_pub_ |
ros::Subscriber | nav_sat_sub_ |
ros::Subscriber | optimize_sub_ |
double | rotation_ |
tf2_ros::TransformBroadcaster | tf_broadcaster |
tf2_ros::Buffer | tf_buffer |
tf2_ros::TransformListener | tf_listener |
std::array< double, 2 > | translation_ |
std::vector< ros::WallTimer > | wall_timers_ |
std::vector< Eigen::Matrix< double, 2, 1 > > | world_poses_ |
bool | write_debug_file_ |
Definition at line 42 of file hector_gps_calibration.h.
GPSCalibration::GPSCalibration | ( | ros::NodeHandle & | nh | ) |
Definition at line 12 of file hector_gps_calibration.cpp.
|
private |
Definition at line 56 of file hector_gps_calibration.cpp.
|
private |
Definition at line 107 of file hector_gps_calibration.cpp.
|
private |
Definition at line 101 of file hector_gps_calibration.cpp.
|
private |
Definition at line 161 of file hector_gps_calibration.cpp.
|
private |
Definition at line 61 of file hector_gps_calibration.h.
|
private |
Definition at line 59 of file hector_gps_calibration.h.
|
private |
Definition at line 74 of file hector_gps_calibration.h.
|
private |
Definition at line 75 of file hector_gps_calibration.h.
|
private |
Definition at line 66 of file hector_gps_calibration.h.
|
private |
Definition at line 63 of file hector_gps_calibration.h.
|
private |
Definition at line 64 of file hector_gps_calibration.h.
|
private |
Definition at line 71 of file hector_gps_calibration.h.
|
private |
Definition at line 57 of file hector_gps_calibration.h.
|
private |
Definition at line 55 of file hector_gps_calibration.h.
|
private |
Definition at line 56 of file hector_gps_calibration.h.
|
private |
Definition at line 70 of file hector_gps_calibration.h.
|
private |
Definition at line 68 of file hector_gps_calibration.h.
|
private |
Definition at line 60 of file hector_gps_calibration.h.
|
private |
Definition at line 73 of file hector_gps_calibration.h.