Go to the documentation of this file.
37 #ifndef POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_
38 #define POSE_BASE_CONTROLLER_POSE_BASE_CONTROLLER_H_
47 #include <move_base_msgs/MoveBaseAction.h>
48 #include <geometry_msgs/PoseStamped.h>
49 #include <geometry_msgs/Pose.h>
50 #include <geometry_msgs/Twist.h>
51 #include <nav_msgs/Odometry.h>
53 #include <boost/thread.hpp>
65 void execute(
const move_base_msgs::MoveBaseGoalConstPtr& user_goal);
66 bool controlLoop(
const move_base_msgs::MoveBaseGoal& current_goal);
69 inline double sign(
double n){
70 return n < 0.0 ? -1.0 : 1.0;
74 geometry_msgs::Twist
limitTwist(
const geometry_msgs::Twist& twist);
75 double headingDiff(
double pt_x,
double pt_y,
double x,
double y,
double heading);
76 move_base_msgs::MoveBaseGoal
goalToFixedFrame(
const move_base_msgs::MoveBaseGoal& goal);
79 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
nav_msgs::Odometry base_odom_
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
geometry_msgs::Twist diff2D(const tf2::Transform &pose1, const tf2::Transform &pose2)
tf2::Stamped< tf2::Transform > getRobotPose()
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
double in_place_trans_vel_
MoveBaseActionServer action_server_
bool controlLoop(const move_base_msgs::MoveBaseGoal ¤t_goal)
void execute(const move_base_msgs::MoveBaseGoalConstPtr &user_goal)
tf2_ros::TransformListener tfl_
move_base_msgs::MoveBaseGoal goalToFixedFrame(const move_base_msgs::MoveBaseGoal &goal)
double min_in_place_vel_th_
ros::Subscriber odom_sub_
double rot_stopped_velocity_
double tolerance_timeout_
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
double trans_stopped_velocity_
double transform_tolerance_