00001 /* 00002 * Obstacle avoidance with LaserScan. 00003 * 00004 * Drive the robot while avoiding obstacles: 00005 * - onTraverse and onContinue: go more or less forward depending 00006 * on obstacle position. The action never stops by itself. 00007 * 00008 * Interaction with the map (created by this jockey): 00009 * - none. 00010 * 00011 * Interaction with the map (created by other jockeys): 00012 * - none. 00013 * 00014 * Subscribers (other than map-related): 00015 * - message type, topic default name, description 00016 * - sensor_msgs/LaserScan, "~base_scan", laser-scan at the front of the 00017 * robot. 00018 * 00019 * Publishers (other than map-related): 00020 * - message type, topic default name, description 00021 * - geometry_msgs/Twist, "~cmd_vel", set velocity. 00022 * 00023 * Services used (other than map-related): 00024 * - none. 00025 * 00026 * Parameters: 00027 * - ~robot_radius, Float, NO_DEFAULT, robot radius (m). 00028 * - ~min_distance, Float, 2 * robot_radius, if an obstacle is closer than this, 00029 * turn and don't go forward (m). 00030 * - ~long_distance, Float, 5 * robot_radius, if no obstacle within this 00031 * distance, go straight (m). 00032 * - ~short_lateral_distance, Float, 2 * robot_radius, if obstacle within 00033 * this lateral distance, turn and don't go forward (m). 00034 * - ~long_lateral_distance, Float, 3 * robot_radius, if no obstacle within 00035 * this lateral distance, go straight (m). 00036 * - ~force_turn_left_factor, Float, 3, if the mean obstacle distance is 00037 * smaller that this factor times min_distance, force a left turn to avoid 00038 * oscillating in front of a corner. 00039 * - ~turnrate_collide, Float, 0.4, turn rate when obstacle closer than 00040 * min_distance_ (rad/s). 00041 * - ~max_vel, Float, 1.0, linear velocity without obstacle (m/s). 00042 * - ~vel_close_obstacle, Float, 0.5, linear velocity if obstacle between 00043 * min_distance and long_distance (m/s). 00044 * - ~turnrate_factor, Float, 0.9, if obstacle closer than long_distance 00045 * turnrate = -turnrate_factor_ * mean(lateral_position_of_obstacle) 00046 * (rad.m^-1.s^-1). 00047 */ 00048 00049 #ifndef NJ_OA_LASER_JOCKEY_H 00050 #define NJ_OA_LASER_JOCKEY_H 00051 00052 #include <cmath> 00053 00054 #include <sensor_msgs/LaserScan.h> 00055 #include <geometry_msgs/Twist.h> 00056 00057 #include <lama_jockeys/navigating_jockey.h> 00058 00059 #include <nj_oa_laser/twist_handler.h> 00060 00061 namespace nj_oa_laser 00062 { 00063 00064 class Jockey : public lama_jockeys::NavigatingJockey 00065 { 00066 public : 00067 00068 Jockey(const std::string& name, const double robot_radius); 00069 00070 void initTwistHandlerParam(TwistHandler& twist_handler); 00071 00072 virtual void onTraverse(); 00073 virtual void onStop(); 00074 virtual void onInterrupt(); 00075 virtual void onContinue(); 00076 00077 protected: 00078 00079 // Subscribers and publishers. 00080 ros::Publisher pub_twist_; 00081 00082 private : 00083 00084 void handleLaser(const sensor_msgs::LaserScanConstPtr& msg); 00085 00086 // Internals. 00087 TwistHandler twist_handler_; 00088 00089 }; 00090 00091 } // namespace nj_oa_laser 00092 00093 #endif // NJ_OA_LASER_JOCKEY_H