00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef POSE_FOLLOWER_POSE_FOLLOWER_H_
00038 #define POSE_FOLLOWER_POSE_FOLLOWER_H_
00039 #include <ros/ros.h>
00040 #include <tf/tf.h>
00041 #include <tf/transform_datatypes.h>
00042 #include <tf/transform_listener.h>
00043 #include <nav_core/base_local_planner.h>
00044 #include <costmap_2d/costmap_2d_ros.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <geometry_msgs/Twist.h>
00047 #include <nav_msgs/Odometry.h>
00048 #include <base_local_planner/trajectory_planner_ros.h>
00049
00050 namespace pose_follower {
00051 class PoseFollower : public nav_core::BaseLocalPlanner {
00052 public:
00053 PoseFollower();
00054 void initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
00055 bool isGoalReached();
00056 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
00057 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00058
00059 private:
00060 inline double sign(double n){
00061 return n < 0.0 ? -1.0 : 1.0;
00062 }
00063
00064 geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose& pose2);
00065 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00066 double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
00067
00068 bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00069 const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
00070 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
00071
00072 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00073 bool stopped();
00074
00075 tf::TransformListener* tf_;
00076 costmap_2d::Costmap2DROS* costmap_ros_;
00077 ros::Publisher vel_pub_;
00078 double K_trans_, K_rot_, tolerance_trans_, tolerance_rot_;
00079 double tolerance_timeout_;
00080 double max_vel_lin_, max_vel_th_;
00081 double min_vel_lin_, min_vel_th_;
00082 double min_in_place_vel_th_, in_place_trans_vel_;
00083 bool holonomic_;
00084 boost::mutex odom_lock_;
00085 ros::Subscriber odom_sub_;
00086 nav_msgs::Odometry base_odom_;
00087 double trans_stopped_velocity_, rot_stopped_velocity_;
00088 ros::Time goal_reached_time_;
00089 unsigned int current_waypoint_;
00090 std::vector<geometry_msgs::PoseStamped> global_plan_;
00091 base_local_planner::TrajectoryPlannerROS collision_planner_;
00092 int samples_;
00093 };
00094 };
00095 #endif