00001 /* Action server for the memory-less navigating jockey based on LaserScan. 00002 * 00003 * The role of this jockey is to travel to the next crossing. 00004 * Implemented actions: 00005 * - TRAVERSE: will start navigating to the next crossing (place with at least 00006 * three frontiers) and will succeed when the crossing center is reached. 00007 * - STOP: will stop 00008 * - INTERRUPT: same as CONTINUE 00009 * - CONTINUE: same as TRAVERSE 00010 * 00011 * Interaction with the map: 00012 * - Getter: none 00013 * - Setter: none. 00014 * 00015 * Subscribers (other than map-related): 00016 * - sensor_msg/LaserScan, "~/base_scan", 360-deg laser-scan. 00017 * 00018 * Publishers (other than map-related): 00019 * - visualization_msgs/Marker, "~crossing_marker", a sphere at the crossing center. 00020 * - visualization_msgs/Marker, "~exits_marker", lines from crossing center towards exits. 00021 * - geometry_msgs/Twist, "~cmd_vel", set velocity. 00022 * - sensor_msgs/PointCloud, "~place_profile_cloud", profile of the surroundings. 00023 * - lama_msgs/Crossing, "~crossing", computed Crossing 00024 * 00025 * Parameters: 00026 * - ~range_cutoff, Float, NO_DEFAULT, points farther than this are cut and 00027 * frontier may exist. 00028 * - ~robot_radius, Float, frontier_width/2, robot radius (frontier_width is 00029 * a constructor parameter) 00030 */ 00031 00032 #ifndef _NJ_LASER_JOCKEY_H_ 00033 #define _NJ_LASER_JOCKEY_H_ 00034 00035 #include <sensor_msgs/LaserScan.h> 00036 00037 #include <crossing_detector/laser_crossing_detector.h> 00038 #include <goto_crossing/crossing_goer.h> 00039 #include <lama_common/crossing_visualization.h> 00040 #include <lama_jockeys/navigating_jockey.h> 00041 #include <nj_oa_laser/twist_handler.h> 00042 00043 #include <nj_laser/visualization.h> 00044 00045 namespace nj_laser 00046 { 00047 00048 class Jockey : public lama_jockeys::NavigatingJockey 00049 { 00050 public: 00051 00052 Jockey(const std::string& name, const double frontier_width); 00053 00054 virtual void onTraverse(); 00055 virtual void onStop(); 00056 virtual void onInterrupt(); 00057 virtual void onContinue(); 00058 00059 void handleLaser(const sensor_msgs::LaserScanConstPtr& msg); 00060 00061 private: 00062 00063 // Subscribers and publishers. 00064 ros::Subscriber laserHandler_; 00065 ros::Publisher pub_crossing_marker_; 00066 ros::Publisher pub_exits_marker_; 00067 ros::Publisher pub_twist_; 00068 ros::Publisher pub_place_profile_; 00069 ros::Publisher pub_crossing_; 00070 00071 // Parameters shown outside. 00072 double range_cutoff_; 00073 00074 // Internals. 00075 bool has_crossing_; 00076 sensor_msgs::LaserScan scan_; 00077 lama_msgs::Crossing crossing_; 00078 crossing_detector::LaserCrossingDetector crossing_detector_; 00079 goto_crossing::CrossingGoer crossing_goer_; 00080 nj_oa_laser::TwistHandler obstacle_avoider_; 00081 }; 00082 00083 } // namespace nj_laser 00084 00085 #endif // _NJ_LASER_JOCKEY_H_ 00086