41 action_server_(
ros::NodeHandle(),
42 "pose_base_controller",
46 node_private.param(
"k_trans", K_trans_, 1.0);
47 node_private.param(
"k_rot", K_rot_, 1.0);
49 node_private.param(
"tolerance_trans", tolerance_trans_, 0.02);
50 node_private.param(
"tolerance_rot", tolerance_rot_, 0.04);
51 node_private.param(
"tolerance_timeout", tolerance_timeout_, 0.5);
53 node_private.param(
"fixed_frame", fixed_frame_, std::string(
"odom_combined"));
54 node_private.param(
"base_frame", base_frame_, std::string(
"base_link"));
56 node_private.param(
"holonomic", holonomic_,
true);
58 node_private.param(
"max_vel_lin", max_vel_lin_, 0.9);
59 node_private.param(
"max_vel_th", max_vel_th_, 1.4);
61 node_private.param(
"min_vel_lin", min_vel_lin_, 0.0);
62 node_private.param(
"min_vel_th", min_vel_th_, 0.0);
63 node_private.param(
"min_in_place_vel_th", min_in_place_vel_th_, 0.0);
64 node_private.param(
"in_place_trans_vel", in_place_trans_vel_, 0.0);
65 node_private.param(
"frequency", freq_, 100.0);
66 node_private.param(
"transform_tolerance", transform_tolerance_, 0.5);
68 node_private.param(
"trans_stopped_velocity", trans_stopped_velocity_, 1e-4);
69 node_private.param(
"rot_stopped_velocity", rot_stopped_velocity_, 1e-4);
72 odom_sub_ = node.
subscribe<nav_msgs::Odometry>(
"odom", 1, boost::bind(&PoseBaseController::odomCallback,
this, _1));
73 vel_pub_ = node.
advertise<geometry_msgs::Twist>(
"base_controller/command", 10);
75 action_server_.start();
79 void PoseBaseController::odomCallback(
const nav_msgs::Odometry::ConstPtr& msg){
81 boost::mutex::scoped_lock lock(odom_lock_);
82 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
83 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
84 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
85 ROS_DEBUG(
"In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
86 base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
89 double PoseBaseController::headingDiff(
double x,
double y,
double pt_x,
double pt_y,
double heading)
91 double v1_x = x - pt_x;
92 double v1_y = y - pt_y;
93 double v2_x = cos(heading);
94 double v2_y = sin(heading);
96 double perp_dot = v1_x * v2_y - v1_y * v2_x;
97 double dot = v1_x * v2_x + v1_y * v2_y;
100 double vector_angle = atan2(perp_dot, dot);
102 return -1.0 * vector_angle;
106 geometry_msgs::PoseStamped global_pose, robot_pose;
107 robot_pose.pose.orientation.w = 1.0;
108 robot_pose.header.frame_id = base_frame_;
110 tf_.transform(robot_pose, global_pose, fixed_frame_);
115 return global_pose_tf;
118 move_base_msgs::MoveBaseGoal PoseBaseController::goalToFixedFrame(
const move_base_msgs::MoveBaseGoal& goal){
119 move_base_msgs::MoveBaseGoal fixed_goal;
120 geometry_msgs::PoseStamped pose;
121 pose = goal.target_pose;
128 tf_.transform(pose, fixed_goal.target_pose, fixed_frame_);
131 ROS_WARN(
"Failed to transform the goal pose from %s into the %s frame: %s",
132 pose.header.frame_id.c_str(), fixed_frame_.c_str(), ex.what());
139 void PoseBaseController::execute(
const move_base_msgs::MoveBaseGoalConstPtr& user_goal){
140 bool success =
false;
142 move_base_msgs::MoveBaseGoal goal = goalToFixedFrame(*user_goal);
144 success = controlLoop(goal);
151 geometry_msgs::Twist empty_twist;
152 vel_pub_.publish(empty_twist);
155 action_server_.setSucceeded();
159 if(action_server_.isPreemptRequested())
160 action_server_.setPreempted();
162 action_server_.setAborted();
166 bool PoseBaseController::stopped(){
168 nav_msgs::Odometry base_odom;
170 boost::mutex::scoped_lock lock(odom_lock_);
171 base_odom = base_odom_;
174 return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_
175 && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_
176 && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_;
179 bool PoseBaseController::controlLoop(
const move_base_msgs::MoveBaseGoal& current_goal){
186 if(action_server_.isPreemptRequested()){
196 robot_pose = getRobotPose();
199 ROS_WARN(
"The %s frame to %s frame transform is more than %.2f seconds old, will not move",
200 fixed_frame_.c_str(), base_frame_.c_str(), transform_tolerance_);
201 geometry_msgs::Twist empty_twist;
202 vel_pub_.publish(empty_twist);
207 ROS_ERROR(
"Can't transform: %s\n", ex.what());
208 geometry_msgs::Twist empty_twist;
209 vel_pub_.publish(empty_twist);
212 ROS_DEBUG(
"PoseBaseController: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(),
tf2::getYaw(robot_pose.getRotation()));
213 ROS_DEBUG(
"PoseBaseController: target robot pose %f %f ==> %f", target_pose.getOrigin().x(), target_pose.getOrigin().y(),
tf2::getYaw(target_pose.getRotation()));
216 geometry_msgs::Twist diff = diff2D(target_pose, robot_pose);
217 ROS_DEBUG(
"PoseBaseController: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
220 vel_pub_.publish(limitTwist(diff));
223 if (fabs(diff.linear.x) > tolerance_trans_ || fabs(diff.linear.y) > tolerance_trans_ || fabs(diff.angular.z) > tolerance_rot_)
228 geometry_msgs::Twist empty_twist;
229 vel_pub_.publish(empty_twist);
240 geometry_msgs::Twist res;
246 if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_))
261 if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
262 ROS_DEBUG(
"Negative is better: %.2f", neg_yaw_diff);
263 yaw_diff = neg_yaw_diff;
268 rot_diff.
setRPY(0.0, 0.0, yaw_diff);
281 geometry_msgs::Twist PoseBaseController::limitTwist(
const geometry_msgs::Twist& twist)
283 geometry_msgs::Twist res = twist;
284 res.linear.x *= K_trans_;
288 res.linear.y *= K_trans_;
289 res.angular.z *= K_rot_;
292 double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
293 if (lin_overshoot > 1.0)
295 res.linear.x /= lin_overshoot;
296 res.linear.y /= lin_overshoot;
298 if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z);
299 if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
301 if(fabs(res.linear.x) < in_place_trans_vel_ && fabs(res.linear.y) < in_place_trans_vel_){
302 if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
305 ROS_DEBUG(
"Angular command %f", res.angular.z);
310 int main(
int argc,
char** argv)
312 ros::init(argc, argv,
"pose_base_controller");