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
00062 #ifndef NAV_PCONTROLLER_H
00063 #define NAV_PCONTROLLER_H
00064
00065 #include <ros/ros.h>
00066 #include <ros/time.h>
00067 #include "tf/transform_listener.h"
00068 #include <actionlib/server/simple_action_server.h>
00069
00070 #include <string>
00071
00072 #include <boost/thread.hpp>
00073
00074 #include <geometry_msgs/PoseStamped.h>
00075 #include <move_base_msgs/MoveBaseAction.h>
00076
00077 #include "BaseDistance.h"
00078
00079 class BasePController {
00080 private:
00081
00082 double xy_tolerance_, th_tolerance_;
00083 ros::Duration fail_timeout_;
00084 double fail_velocity_;
00085 double vel_ang_max_, vel_lin_max_, acc_ang_max_, acc_lin_max_, p_;
00086 int loop_rate_;
00087
00088 double vx_, vy_, vth_;
00089 double x_goal_, y_goal_, th_goal_;
00090 double x_now_, y_now_, th_now_;
00091 bool goal_set_, keep_distance_;
00092
00093 double laser_watchdog_timeout_;
00094
00095 std::string global_frame_;
00096 std::string base_link_frame_;
00097
00098 BaseDistance dist_control_;
00099
00100 ros::NodeHandle n_;
00101 tf::TransformListener tf_;
00102 ros::Subscriber sub_goal_;
00103 ros::Publisher pub_vel_;
00104
00105 ros::Time low_speed_time_;
00106
00107 boost::mutex lock;
00108
00109 void newGoal(const geometry_msgs::PoseStamped &msg);
00110 void newGoal(const geometry_msgs::PoseStamped::ConstPtr& msg);
00111
00112 void cycle();
00113 void stopRobot();
00114 void sendVelCmd(double vx, double vy, double vth);
00115 bool comparePoses(double x1, double y1, double a1,
00116 double x2, double y2, double a2);
00117
00118 bool retrieve_pose();
00119 double p_control(double x, double p, double limit);
00120 double limit_acc(double x, double x_old, double limit);
00121 void compute_p_control();
00122
00123 void parseParams();
00124
00125 actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> move_base_actionserver_;
00126
00127 void newMoveBaseGoal();
00128 void preemptMoveBaseGoal();
00129
00130 public:
00131 BasePController();
00132 ~BasePController();
00133 void main();
00134 };
00135
00136 #endif