Go to the documentation of this file.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 #ifndef HECTOR_PATH_FOLLOWER_H_
00033 #define HECTOR_PATH_FOLLOWER_H_
00034 #include <ros/ros.h>
00035 #include <tf/tf.h>
00036 #include <tf/transform_datatypes.h>
00037 #include <tf/transform_listener.h>
00038 #include <geometry_msgs/PoseStamped.h>
00039 #include <geometry_msgs/Twist.h>
00040
00041 namespace pose_follower {
00042 class HectorPathFollower
00043 {
00044 public:
00045 HectorPathFollower();
00046 void initialize(tf::TransformListener* tf);
00047 bool isGoalReached();
00048 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
00049 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00050
00051 private:
00052 inline double sign(double n){
00053 return n < 0.0 ? -1.0 : 1.0;
00054 }
00055
00056 geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose& pose2);
00057 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00058 double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
00059
00060 bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, const std::string& global_frame,
00061 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
00062
00063
00064 bool stopped();
00065
00066 bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const;
00067
00068 tf::TransformListener* tf_;
00069
00070 double K_trans_, K_rot_, tolerance_trans_, tolerance_rot_;
00071 double tolerance_timeout_;
00072 double max_vel_lin_, max_vel_th_;
00073 double min_vel_lin_, min_vel_th_;
00074 double min_in_place_vel_th_, in_place_trans_vel_;
00075 bool holonomic_;
00076 std::string p_robot_base_frame_;
00077 std::string p_global_frame_;
00078
00079 boost::mutex odom_lock_;
00080 ros::Subscriber odom_sub_;
00081
00082 double trans_stopped_velocity_, rot_stopped_velocity_;
00083 ros::Time goal_reached_time_;
00084 unsigned int current_waypoint_;
00085 std::vector<geometry_msgs::PoseStamped> global_plan_;
00086
00087 int samples_;
00088 };
00089 };
00090 #endif