19 #ifndef LOCALIZATION_ANALYSIS_MAP_MATCHER_H_
20 #define LOCALIZATION_ANALYSIS_MAP_MATCHER_H_
22 #include <ff_msgs/VisualLandmarks.h>
27 #include <rosbag/view.h>
29 #include <gtsam/geometry/Pose3.h>
36 MapMatcher(
const std::string& input_bag_name,
const std::string& map_file,
const std::string& image_topic,
37 const std::string& output_bag_name,
const std::string& save_noloc_imgs =
"");
42 bool GenerateVLFeatures(
const sensor_msgs::ImageConstPtr& image_msg, ff_msgs::VisualLandmarks& vl_features);
44 rosbag::Bag input_bag_;
45 rosbag::Bag output_bag_;
46 rosbag::Bag nonloc_bag_;
47 std::string image_topic_;
50 gtsam::Pose3 body_T_nav_cam_;
52 int sparse_mapping_min_num_landmarks_;
58 #endif // LOCALIZATION_ANALYSIS_MAP_MATCHER_H_