37 #ifndef POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_ 38 #define POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_ 43 #include <move_base_msgs/MoveBaseAction.h> 44 #include <geometry_msgs/PoseStamped.h> 45 #include <geometry_msgs/Pose.h> 46 #include <geometry_msgs/Twist.h> 47 #include <nav_msgs/Odometry.h> 49 #include <boost/thread.hpp> 61 void execute(
const move_base_msgs::MoveBaseGoalConstPtr& user_goal);
62 bool controlLoop(
const move_base_msgs::MoveBaseGoal& current_goal);
65 inline double sign(
double n){
66 return n < 0.0 ? -1.0 : 1.0;
70 geometry_msgs::Twist
limitTwist(
const geometry_msgs::Twist& twist);
71 double headingDiff(
double pt_x,
double pt_y,
double x,
double y,
double heading);
72 move_base_msgs::MoveBaseGoal
goalToFixedFrame(
const move_base_msgs::MoveBaseGoal& goal);
75 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
MoveBaseActionServer action_server_
double transform_tolerance_
TFSIMD_FORCE_INLINE const tfScalar & y() const
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
double tolerance_timeout_
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void execute(const move_base_msgs::MoveBaseGoalConstPtr &user_goal)
double rot_stopped_velocity_
double in_place_trans_vel_
bool controlLoop(const move_base_msgs::MoveBaseGoal ¤t_goal)
TFSIMD_FORCE_INLINE const tfScalar & x() const
tf::Stamped< tf::Pose > getRobotPose()
tf::TransformListener tf_
ros::Subscriber odom_sub_
double min_in_place_vel_th_
nav_msgs::Odometry base_odom_
move_base_msgs::MoveBaseGoal goalToFixedFrame(const move_base_msgs::MoveBaseGoal &goal)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
double trans_stopped_velocity_