00001 /* 00002 * Short description. 00003 * 00004 * Long description: 00005 * - description of general role 00006 * - description of used actions with associated result (DONE when, FAIL if...) 00007 * 00008 * Interaction with the map (created by this jockey): 00009 * - [Getter][/][Setter], message type, interface default name 00010 * - Getter/Setter: VectorLaserScan, jockey_name + "_laser_descriptor" 00011 * 00012 * Interaction with the map (created by other jockeys): 00013 * - [Getter][/][Setter], message type, interface default name 00014 * - Getter: VectorLaserScan, "laser_descriptor" 00015 * 00016 * Subscribers (other than map-related): 00017 * - message type, topic default name, description 00018 * - sensor_msgs::LaserScan, "~/base_scan", 360-deg laser-scan. 00019 * 00020 * Publishers (other than map-related): 00021 * - message type, topic default name, description 00022 * - nav_msgs::Pose, "~/pose", robot pose 00023 * 00024 * Services used (other than map-related): 00025 * - service type, server default name, description 00026 * - place_matcher_msgs::PolygonDissimilarity, "~/dissimilarity_server", used to 00027 * compare all known places with the current place 00028 * 00029 * Parameters: 00030 * - name, type, default value, description 00031 */ 00032 00033 #ifndef PLACE_MATCHER_MCC_JOCKEY_H 00034 #define PLACE_MATCHER_MCC_JOCKEY_H 00035 00036 #include <vector> 00037 00038 #include <geometry_msgs/Polygon.h> 00039 #include <lama_interfaces/ActOnMap.h> 00040 #include <lama_interfaces/AddInterface.h> 00041 #include <lama_jockeys/localizing_jockey.h> 00042 #include <lama_msgs/GetPlaceProfile.h> 00043 00044 #include <place_matcher_mcc/dissimilarity_getter.h> 00045 00046 namespace place_matcher_mcc 00047 { 00048 00049 class Jockey : public lama_jockeys::LocalizingJockey 00050 { 00051 public : 00052 00053 Jockey(const std::string& name); 00054 00055 void onGetDissimilarity(); 00056 00057 double getSampleCount() {return dissimilarity_getter_.sample_count;} 00058 void setSampleCount(double sample_count) {dissimilarity_getter_.sample_count = sample_count;} 00059 00060 double getScaleCount() {return dissimilarity_getter_.scale_count;} 00061 void setScaleCount(double scale_count) {dissimilarity_getter_.scale_count = scale_count;} 00062 00063 bool getRotationInvariance() {return dissimilarity_getter_.rotation_invariance;} 00064 void setRotationInvariance(bool rotation_invariance) {dissimilarity_getter_.rotation_invariance = rotation_invariance;} 00065 00066 private : 00067 00068 void initMapPlaceProfileInterface(); 00069 void getData(); 00070 void handlePolygon(const geometry_msgs::PolygonConstPtr& msg); 00071 00072 // Map interface for PlaceProfile descriptors. 00073 std::string place_profile_interface_name_; 00074 bool place_profile_interface_name_defined_; 00075 std::string place_profile_getter_service_name_; 00076 00077 DissimilarityGetter dissimilarity_getter_; 00078 bool has_polygon_data_; 00079 geometry_msgs::Polygon current_polygon_; 00080 00081 }; 00082 00083 } /* namespace place_matcher_mcc */ 00084 00085 #endif /* PLACE_MATCHER_MCC_JOCKEY_H */ 00086