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>
47 void ReadParams(
void);
48 bool ResetMap(
const std::string& map_file);
51 void ImageCallback(
const sensor_msgs::ImageConstPtr& msg);
52 bool EnableService(ff_msgs::SetBool::Request & req, ff_msgs::SetBool::Response & res);
53 bool ResetMapService(ff_msgs::ResetMap::Request & req, ff_msgs::ResetMap::Response & res);
55 std::shared_ptr<Localizer> inst_;
56 std::shared_ptr<sparse_mapping::SparseMap> map_;
57 std::shared_ptr<std::thread> thread_;
59 ros::Timer config_timer_;
61 std::shared_ptr<image_transport::ImageTransport> it_;
62 image_transport::Subscriber image_sub_;
63 ros::ServiceServer enable_srv_, reset_map_srv_;
64 ros::ServiceClient reset_map_loc_client_;
65 ros::Publisher registration_publisher_, landmark_publisher_,
66 detected_features_publisher_, used_features_publisher_, all_features_publisher_;
70 bool matched_features_on_, all_features_on_;
71 cv_bridge::CvImageConstPtr image_ptr_;
73 volatile bool processing_image_;
74 pthread_mutex_t mutex_features_;
75 pthread_cond_t cond_features_;
80 #endif // LOCALIZATION_NODE_LOCALIZATION_NODELET_H_