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
00030
00031
00032
00033
00034
00035
00036
00037 #include <pr2_navigation_controllers/pose_follower.h>
00038 #include <pluginlib/class_list_macros.h>
00039
00040 PLUGINLIB_DECLARE_CLASS(pr2_navigation_controllers, PoseFollower, pr2_navigation_controllers::PoseFollower, nav_core::BaseLocalPlanner)
00041
00042 namespace pr2_navigation_controllers {
00043 PoseFollower::PoseFollower(): tf_(NULL), costmap_ros_(NULL) {}
00044
00045 void PoseFollower::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros){
00046 tf_ = tf;
00047 costmap_ros_ = costmap_ros;
00048 current_waypoint_ = 0;
00049 goal_reached_time_ = ros::Time::now();
00050 ros::NodeHandle node_private("~/" + name);
00051
00052 collision_planner_.initialize(name, tf_, costmap_ros_);
00053
00054 node_private.param("k_trans", K_trans_, 2.0);
00055 node_private.param("k_rot", K_rot_, 2.0);
00056
00057 node_private.param("tolerance_trans", tolerance_trans_, 0.02);
00058 node_private.param("tolerance_rot", tolerance_rot_, 0.04);
00059 node_private.param("tolerance_timeout", tolerance_timeout_, 0.5);
00060
00061 node_private.param("holonomic", holonomic_, true);
00062
00063 node_private.param("samples", samples_, 10);
00064
00065 node_private.param("max_vel_lin", max_vel_lin_, 0.9);
00066 node_private.param("max_vel_th", max_vel_th_, 1.4);
00067
00068 node_private.param("min_vel_lin", min_vel_lin_, 0.1);
00069 node_private.param("min_vel_th", min_vel_th_, 0.0);
00070 node_private.param("min_in_place_vel_th", min_in_place_vel_th_, 0.0);
00071 node_private.param("in_place_trans_vel", in_place_trans_vel_, 0.0);
00072
00073 node_private.param("trans_stopped_velocity", trans_stopped_velocity_, 1e-4);
00074 node_private.param("rot_stopped_velocity", rot_stopped_velocity_, 1e-4);
00075
00076 ros::NodeHandle node;
00077 odom_sub_ = node.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&PoseFollower::odomCallback, this, _1));
00078 vel_pub_ = node.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00079
00080 ROS_DEBUG("Initialized");
00081 }
00082
00083 void PoseFollower::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){
00084
00085 boost::mutex::scoped_lock lock(odom_lock_);
00086 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
00087 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
00088 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
00089 ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
00090 base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
00091 }
00092
00093 double PoseFollower::headingDiff(double x, double y, double pt_x, double pt_y, double heading)
00094 {
00095 double v1_x = x - pt_x;
00096 double v1_y = y - pt_y;
00097 double v2_x = cos(heading);
00098 double v2_y = sin(heading);
00099
00100 double perp_dot = v1_x * v2_y - v1_y * v2_x;
00101 double dot = v1_x * v2_x + v1_y * v2_y;
00102
00103
00104 double vector_angle = atan2(perp_dot, dot);
00105
00106 return -1.0 * vector_angle;
00107 }
00108
00109 bool PoseFollower::stopped(){
00110
00111 nav_msgs::Odometry base_odom;
00112 {
00113 boost::mutex::scoped_lock lock(odom_lock_);
00114 base_odom = base_odom_;
00115 }
00116
00117 return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_
00118 && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_
00119 && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_;
00120 }
00121
00122 bool PoseFollower::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
00123
00124 tf::Stamped<tf::Pose> robot_pose;
00125 if(!costmap_ros_->getRobotPose(robot_pose)){
00126 ROS_ERROR("Can't get robot pose");
00127 geometry_msgs::Twist empty_twist;
00128 cmd_vel = empty_twist;
00129 return false;
00130 }
00131
00132
00133 tf::Stamped<tf::Pose> target_pose;
00134 tf::poseStampedMsgToTF(global_plan_[current_waypoint_], target_pose);
00135
00136 ROS_DEBUG("PoseFollower: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(), tf::getYaw(robot_pose.getRotation()));
00137 ROS_DEBUG("PoseFollower: target robot pose %f %f ==> %f", target_pose.getOrigin().x(), target_pose.getOrigin().y(), tf::getYaw(target_pose.getRotation()));
00138
00139
00140 geometry_msgs::Twist diff = diff2D(target_pose, robot_pose);
00141 ROS_DEBUG("PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
00142
00143 geometry_msgs::Twist limit_vel = limitTwist(diff);
00144
00145 geometry_msgs::Twist test_vel = limit_vel;
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176 cmd_vel = test_vel;
00177
00178 bool in_goal_position = false;
00179 while(fabs(diff.linear.x) <= tolerance_trans_ &&
00180 fabs(diff.linear.y) <= tolerance_trans_ &&
00181 fabs(diff.angular.z) <= tolerance_rot_)
00182 {
00183 if(current_waypoint_ < global_plan_.size() - 1)
00184 {
00185 current_waypoint_++;
00186 tf::poseStampedMsgToTF(global_plan_[current_waypoint_], target_pose);
00187 diff = diff2D(target_pose, robot_pose);
00188 }
00189 else
00190 {
00191 ROS_INFO("Reached goal: %d", current_waypoint_);
00192 in_goal_position = true;
00193 break;
00194 }
00195 }
00196
00197
00198 if(!in_goal_position)
00199 goal_reached_time_ = ros::Time::now();
00200
00201
00202 if(goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now()){
00203 geometry_msgs::Twist empty_twist;
00204 cmd_vel = empty_twist;
00205 }
00206
00207 return true;
00208 }
00209
00210 bool PoseFollower::setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan){
00211 current_waypoint_ = 0;
00212 goal_reached_time_ = ros::Time::now();
00213 if(!transformGlobalPlan(*tf_, global_plan, *costmap_ros_, costmap_ros_->getGlobalFrameID(), global_plan_)){
00214 ROS_ERROR("Could not transform the global plan to the frame of the controller");
00215 return false;
00216 }
00217 return true;
00218 }
00219
00220 bool PoseFollower::isGoalReached(){
00221 if(goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now() && stopped()){
00222 return true;
00223 }
00224 return false;
00225 }
00226
00227 geometry_msgs::Twist PoseFollower::diff2D(const tf::Pose& pose1, const tf::Pose& pose2)
00228 {
00229 geometry_msgs::Twist res;
00230 tf::Pose diff = pose2.inverse() * pose1;
00231 res.linear.x = diff.getOrigin().x();
00232 res.linear.y = diff.getOrigin().y();
00233 res.angular.z = tf::getYaw(diff.getRotation());
00234
00235 if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_))
00236 return res;
00237
00238
00239
00240
00241
00242 double yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(),
00243 pose2.getOrigin().x(), pose2.getOrigin().y(), tf::getYaw(pose2.getRotation()));
00244
00245
00246 double neg_yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(),
00247 pose2.getOrigin().x(), pose2.getOrigin().y(), M_PI + tf::getYaw(pose2.getRotation()));
00248
00249
00250 if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
00251 ROS_DEBUG("Negative is better: %.2f", neg_yaw_diff);
00252 yaw_diff = neg_yaw_diff;
00253 }
00254
00255
00256 tf::Quaternion rot_diff = tf::createQuaternionFromYaw(yaw_diff);
00257 tf::Quaternion rot = pose2.getRotation() * rot_diff;
00258 tf::Pose new_pose = pose1;
00259 new_pose.setRotation(rot);
00260
00261 diff = pose2.inverse() * new_pose;
00262 res.linear.x = diff.getOrigin().x();
00263 res.linear.y = diff.getOrigin().y();
00264 res.angular.z = tf::getYaw(diff.getRotation());
00265 return res;
00266 }
00267
00268
00269 geometry_msgs::Twist PoseFollower::limitTwist(const geometry_msgs::Twist& twist)
00270 {
00271 geometry_msgs::Twist res = twist;
00272 res.linear.x *= K_trans_;
00273 if(!holonomic_)
00274 res.linear.y = 0.0;
00275 else
00276 res.linear.y *= K_trans_;
00277 res.angular.z *= K_rot_;
00278
00279
00280 double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
00281 double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
00282 if (lin_overshoot > 1.0)
00283 {
00284 res.linear.x /= lin_overshoot;
00285 res.linear.y /= lin_overshoot;
00286 }
00287
00288
00289 if(lin_undershoot > 1.0)
00290 {
00291 res.linear.x *= lin_undershoot;
00292 res.linear.y *= lin_undershoot;
00293 }
00294
00295 if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z);
00296 if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
00297
00298
00299 if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_){
00300 if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
00301 res.linear.x = 0.0;
00302 res.linear.y = 0.0;
00303 }
00304
00305 ROS_DEBUG("Angular command %f", res.angular.z);
00306 return res;
00307 }
00308
00309 bool PoseFollower::transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00310 const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
00311 std::vector<geometry_msgs::PoseStamped>& transformed_plan){
00312 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00313
00314 transformed_plan.clear();
00315
00316 try{
00317 if (!global_plan.size() > 0)
00318 {
00319 ROS_ERROR("Recieved plan with zero length");
00320 return false;
00321 }
00322
00323 tf::StampedTransform transform;
00324 tf.lookupTransform(global_frame, ros::Time(),
00325 plan_pose.header.frame_id, plan_pose.header.stamp,
00326 plan_pose.header.frame_id, transform);
00327
00328 tf::Stamped<tf::Pose> tf_pose;
00329 geometry_msgs::PoseStamped newer_pose;
00330
00331 for(unsigned int i = 0; i < global_plan.size(); ++i){
00332 const geometry_msgs::PoseStamped& pose = global_plan[i];
00333 poseStampedMsgToTF(pose, tf_pose);
00334 tf_pose.setData(transform * tf_pose);
00335 tf_pose.stamp_ = transform.stamp_;
00336 tf_pose.frame_id_ = global_frame;
00337 poseStampedTFToMsg(tf_pose, newer_pose);
00338
00339 transformed_plan.push_back(newer_pose);
00340 }
00341 }
00342 catch(tf::LookupException& ex) {
00343 ROS_ERROR("No Transform available Error: %s\n", ex.what());
00344 return false;
00345 }
00346 catch(tf::ConnectivityException& ex) {
00347 ROS_ERROR("Connectivity Error: %s\n", ex.what());
00348 return false;
00349 }
00350 catch(tf::ExtrapolationException& ex) {
00351 ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00352 if (global_plan.size() > 0)
00353 ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
00354
00355 return false;
00356 }
00357
00358 return true;
00359 }
00360 };