19 #ifndef LOCALIZATION_NODE_LOCALIZATION_NODELET_H_
20 #define LOCALIZATION_NODE_LOCALIZATION_NODELET_H_
27 #include <ff_msgs/ResetMap.h>
28 #include <ff_msgs/SetBool.h>
30 #include <nodelet/nodelet.h>
31 #include <image_transport/image_transport.h>
49 void ReadParamsWrapper();
50 bool ReadParams(
bool fatal_failure =
true);
51 bool ResetMap(
const std::string& map_file);
54 void ImageCallback(
const sensor_msgs::ImageConstPtr& msg);
55 bool EnableService(ff_msgs::SetBool::Request & req, ff_msgs::SetBool::Response & res);
56 bool ResetMapService(ff_msgs::ResetMap::Request & req, ff_msgs::ResetMap::Response & res);
58 std::shared_ptr<Localizer> inst_;
59 std::shared_ptr<sparse_mapping::SparseMap> map_;
60 std::shared_ptr<std::thread> thread_;
62 std::string last_valid_map_file_;
63 ros::Timer config_timer_;
65 std::shared_ptr<image_transport::ImageTransport> it_;
66 image_transport::Subscriber image_sub_;
67 ros::ServiceServer enable_srv_, reset_map_srv_;
68 ros::ServiceClient reset_map_loc_client_;
69 ros::Publisher registration_publisher_, landmark_publisher_,
70 detected_features_publisher_, used_features_publisher_, all_features_publisher_;
74 bool matched_features_on_, all_features_on_;
75 cv_bridge::CvImageConstPtr image_ptr_;
77 volatile bool processing_image_;
78 pthread_mutex_t mutex_features_;
79 pthread_cond_t cond_features_;
84 #endif // LOCALIZATION_NODE_LOCALIZATION_NODELET_H_