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
00033
00034
00035
00036
00037 #ifndef POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_
00038 #define POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_
00039 #include <ros/ros.h>
00040 #include <tf/tf.h>
00041 #include <tf/transform_listener.h>
00042 #include <actionlib/server/simple_action_server.h>
00043 #include <move_base_msgs/MoveBaseAction.h>
00044 #include <geometry_msgs/PoseStamped.h>
00045 #include <geometry_msgs/Pose.h>
00046 #include <geometry_msgs/Twist.h>
00047 #include <nav_msgs/Odometry.h>
00048
00049 #include <boost/thread.hpp>
00050
00051 namespace pose_base_controller {
00052 class PoseBaseController {
00053 private:
00054 typedef actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> MoveBaseActionServer;
00055
00056 public:
00057 PoseBaseController();
00058
00059 ~PoseBaseController() {}
00060
00061 void execute(const move_base_msgs::MoveBaseGoalConstPtr& user_goal);
00062 bool controlLoop(const move_base_msgs::MoveBaseGoal& current_goal);
00063 tf::Stamped<tf::Pose> getRobotPose();
00064
00065 inline double sign(double n){
00066 return n < 0.0 ? -1.0 : 1.0;
00067 }
00068
00069 geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose& pose2);
00070 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00071 double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
00072 move_base_msgs::MoveBaseGoal goalToFixedFrame(const move_base_msgs::MoveBaseGoal& goal);
00073
00074 private:
00075 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00076 bool stopped();
00077
00078 MoveBaseActionServer action_server_;
00079 tf::TransformListener tf_;
00080 ros::Publisher vel_pub_;
00081 double K_trans_, K_rot_, tolerance_trans_, tolerance_rot_;
00082 double tolerance_timeout_, freq_;
00083 double max_vel_lin_, max_vel_th_;
00084 double min_vel_lin_, min_vel_th_;
00085 double min_in_place_vel_th_, in_place_trans_vel_;
00086 double transform_tolerance_;
00087 std::string fixed_frame_, base_frame_;
00088 bool holonomic_;
00089 boost::mutex odom_lock_;
00090 ros::Subscriber odom_sub_;
00091 nav_msgs::Odometry base_odom_;
00092 double trans_stopped_velocity_, rot_stopped_velocity_;
00093 };
00094 };
00095 #endif