62 #ifndef NAV_PCONTROLLER_H 63 #define NAV_PCONTROLLER_H 72 #include <boost/thread.hpp> 74 #include <geometry_msgs/PoseStamped.h> 75 #include <move_base_msgs/MoveBaseAction.h> 109 void newGoal(
const geometry_msgs::PoseStamped &msg);
110 void newGoal(
const geometry_msgs::PoseStamped::ConstPtr& msg);
114 void sendVelCmd(
double vx,
double vy,
double vth);
116 double x2,
double y2,
double a2);
119 double p_control(
double x,
double p,
double limit);
120 double limit_acc(
double x,
double x_old,
double limit);
ros::Duration fail_timeout_
double p_control(double x, double p, double limit)
bool retrieve_pose()
retrieves tf pose and updates (x_now_, y_now_, th_now_)
void preemptMoveBaseGoal()
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > move_base_actionserver_
double limit_acc(double x, double x_old, double limit)
BaseDistance dist_control_
void newGoal(const geometry_msgs::PoseStamped &msg)
double laser_watchdog_timeout_
ros::Subscriber sub_goal_
std::string global_frame_
tf::TransformListener tf_
bool comparePoses(double x1, double y1, double a1, double x2, double y2, double a2)
ros::Time low_speed_time_
std::string base_link_frame_
void sendVelCmd(double vx, double vy, double vth)