00001 /* 00002 * Localizing jockey based on LaserScan associated with 00003 * absolute heading. 00004 * 00005 * The role of this jockey is to get the dissimilarity of the LaserScan 00006 * descriptors of all vertices with the current LaserScan. 00007 * The action is done when the dissimilarities are computed. 00008 * Implemented actions: 00009 * - GET_VERTEX_DESCRIPTOR: return the LaserScan and the computed Crossing 00010 * - GET_DISSIMILARITY: return the dissimilarity based on LaserScan 00011 * 00012 * Interaction with the map (created by this jockey through lj_laser/jockey.h): 00013 * - Getter/Setter: VectorLaserScan, jockey_name + "_laser" 00014 * - Setter: Crossing, jockey_name + "_crossing" 00015 * 00016 * Interaction with the map (created by other jockeys): 00017 * - none 00018 * 00019 * Subscribers (other than map-related): 00020 * - sensor_msg/LaserScan, "~/base_scan", 360-deg laser-scan. 00021 * - geometry_msgs/Pose, "~/pose", heading is read from it. 00022 * - nav_msgs/Odometry, "~/odom", heading is read from it. 00023 * 00024 * Publishers (other than map-related): 00025 * - 00026 * Services used (other than map-related): 00027 * - place_matcher_msgs::PolygonDisimilarity, "~/compute_dissimilarity" 00028 */ 00029 00030 #ifndef _LJ_LASER_HEADING_JOCKEY_H_ 00031 #define _LJ_LASER_HEADING_JOCKEY_H_ 00032 00033 #include <geometry_msgs/Pose.h> 00034 #include <nav_msgs/Odometry.h> 00035 #include <geometry_msgs/Quaternion.h> 00036 00037 #include <lj_laser/jockey.h> 00038 00039 namespace lj_laser_heading 00040 { 00041 00042 class Jockey : public lj_laser::Jockey 00043 { 00044 public: 00045 00046 Jockey(std::string name, const double frontier_width, const double max_frontier_angle=0.785); 00047 00048 private: 00049 00050 void initMapLaserInterface(); 00051 void initMapCrossingInterface(); 00052 void handlePose(const geometry_msgs::PoseConstPtr& msg); 00053 void handleOdom(const nav_msgs::OdometryConstPtr& msg); 00054 00055 void getData(); 00056 void rotateScan(); 00057 void handleLaser(const sensor_msgs::LaserScanConstPtr& msg); 00058 00059 // Reception and storage of Odometry and Crossing. 00060 ros::Subscriber poseHandler_; 00061 ros::Subscriber odomHandler_; 00062 ros::Time heading_reception_time_; 00063 double heading_; 00064 00065 // Hard-coded parameters. 00066 const static ros::Duration max_data_time_delta_; 00067 }; 00068 00069 } // namespace lj_laser_heading 00070 00071 #endif // _LJ_LASER_HEADING_JOCKEY_H_