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 #include <ros/ros.h>
00033 #include <tf/transform_datatypes.h>
00034 #include <tf/transform_listener.h>
00035 #include <geometry_msgs/Transform.h>
00036 #include <std_msgs/Bool.h>
00037 #include <std_srvs/Empty.h>
00038 #include <cmath>
00039 #include <geometry_msgs/Pose2D.h>
00040 #include <nav_msgs/Path.h>
00041 #include <geometry_msgs/PoseStamped.h>
00042 #include <move_base_msgs/MoveBaseAction.h>
00043 #include <nao_msgs/FollowPathAction.h>
00044 #include <actionlib/server/simple_action_server.h>
00045 #include <angles/angles.h>
00046 #include <assert.h>
00047
00048 class PathFollower
00049 {
00050 public:
00051 PathFollower();
00052 ~PathFollower();
00053 void goalActionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal);
00054 void pathActionCB(const nao_msgs::FollowPathGoalConstPtr &goal);
00055 void goalCB(const geometry_msgs::PoseStampedConstPtr& goal);
00056 void pathCB(const nav_msgs::PathConstPtr& goal);
00057 bool getRobotPose( tf::StampedTransform & globalToBase, const std::string & global_frame_id);
00058
00059 private:
00060 bool getNextTarget(const nav_msgs::Path & path, const tf::Pose & robotPose, const std::vector<geometry_msgs::PoseStamped>::const_iterator & currentPathPoseIt, tf::Stamped<tf::Transform> & targetPose, std::vector< geometry_msgs::PoseStamped>::const_iterator & targetPathPoseIt);
00061 void stopWalk();
00062 void setVelocity(const tf::Transform& relTarget);
00063 void publishTargetPoseVis(const tf::Stamped<tf::Pose>& targetPose);
00064 void footContactCallback(const std_msgs::BoolConstPtr& contact);
00065 void inhibitJoystick();
00066
00067 ros::NodeHandle nh;
00068 ros::NodeHandle privateNh;
00069 ros::Subscriber m_simpleGoalSub, m_simplePathSub;
00070 ros::Publisher m_targetPub, m_velPub, m_actionGoalPub, m_visPub, m_actionPathPub;
00071 tf::TransformListener m_tfListener;
00072 actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> m_walkGoalServer;
00073 actionlib::SimpleActionServer<nao_msgs::FollowPathAction> m_walkPathServer;
00074 ros::ServiceClient m_inhibitWalkClient, m_uninhibitWalkClient;
00075 ros::Subscriber m_footContactSub;
00076
00077 std::string m_baseFrameId;
00078 double m_controllerFreq;
00079 double m_targetDistThres;
00080 double m_targetAngThres;
00081 double m_waypointDistThres;
00082 double m_waypointAngThres;
00083 bool m_isJoystickInhibited;
00084 bool m_useFootContactProtection;
00085 bool m_footContact;
00086
00087
00088 bool m_useVelocityController;
00089 double m_maxVelFractionX;
00090 double m_maxVelFractionY;
00091 double m_maxVelFractionYaw;
00092 double m_stepFreq;
00093 double m_stepFactor;
00094 const double m_maxVelXY;
00095 const double m_maxVelYaw;
00096 const double m_minStepFreq;
00097 const double m_maxStepFreq;
00098 double m_thresholdFar;
00099 double m_thresholdRotate;
00100 double m_thresholdDampXY;
00101 double m_thresholdDampYaw;
00102
00103 double m_pathNextTargetDistance;
00104 double m_pathStartMaxDistance;
00105 double m_straightMaxRobotDev;
00106 double m_straightMaxRobotYaw;
00107 double m_straightMaxPathDev;
00108 double m_straightThreshold;
00109 double m_straightOffset;
00110 bool m_straight;
00111 };
00112
00113 PathFollower::PathFollower()
00114 : privateNh("~"),
00115 m_walkGoalServer(nh, "walk_target", boost::bind(&PathFollower::goalActionCB, this, _1), false),
00116 m_walkPathServer(nh, "walk_path", boost::bind(&PathFollower::pathActionCB, this, _1), false),
00117 m_baseFrameId("base_footprint"), m_controllerFreq(10),
00118 m_targetDistThres(0.05), m_targetAngThres(angles::from_degrees(5.)),
00119 m_waypointDistThres(0.05), m_waypointAngThres(angles::from_degrees(45)),
00120 m_isJoystickInhibited(false),
00121 m_useFootContactProtection(true), m_footContact(true),
00122 m_useVelocityController(false),
00123 m_maxVelFractionX(0.7), m_maxVelFractionY(0.7), m_maxVelFractionYaw(0.7), m_stepFreq(0.5),
00124 m_maxVelXY(0.0952), m_maxVelYaw(angles::from_degrees(47.6)), m_minStepFreq(1.667), m_maxStepFreq(2.381),
00125 m_thresholdFar(0.20), m_thresholdRotate(angles::from_degrees(45.)),
00126 m_thresholdDampXY(0.20), m_thresholdDampYaw(angles::from_degrees(60.)), m_pathNextTargetDistance(0.1),
00127 m_pathStartMaxDistance(0.1),
00128 m_straightMaxRobotDev(0.1), m_straightMaxRobotYaw(0.25), m_straightMaxPathDev(0.1),
00129 m_straightThreshold(0.2), m_straightOffset(0.3), m_straight(false)
00130 {
00131
00132 privateNh.param("base_frame_id", m_baseFrameId, m_baseFrameId);
00133 m_baseFrameId = m_tfListener.resolve(m_baseFrameId);
00134 privateNh.param("controller_frequency", m_controllerFreq, m_controllerFreq);
00135 privateNh.param("target_distance_threshold", m_targetDistThres, m_targetDistThres);
00136 privateNh.param("target_angle_threshold", m_targetAngThres, m_targetAngThres);
00137 privateNh.param("waypoint_distance_threshold", m_waypointDistThres, m_waypointDistThres);
00138 privateNh.param("waypoint_angle_threshold", m_waypointAngThres, m_waypointAngThres);
00139 privateNh.param("max_vel_x", m_maxVelFractionX, m_maxVelFractionX);
00140 privateNh.param("max_vel_y", m_maxVelFractionY, m_maxVelFractionY);
00141 privateNh.param("max_vel_yaw", m_maxVelFractionYaw, m_maxVelFractionYaw);
00142 privateNh.param("step_freq", m_stepFreq, m_stepFreq);
00143 privateNh.param("use_vel_ctrl", m_useVelocityController, m_useVelocityController);
00144 privateNh.param("use_foot_contact_protection", m_useFootContactProtection, m_useFootContactProtection);
00145 privateNh.param("path_next_target_distance", m_pathNextTargetDistance, m_pathNextTargetDistance);
00146 privateNh.param("path_max_start_distance", m_pathStartMaxDistance, m_pathStartMaxDistance);
00147 privateNh.param("threshold_damp_xy", m_thresholdDampXY, m_thresholdDampXY);
00148 privateNh.param("threshold_damp_yaw", m_thresholdDampYaw, m_thresholdDampYaw);
00149
00150 privateNh.param("straight_max_robot_dev", m_straightMaxRobotDev, m_straightMaxRobotDev);
00151 privateNh.param("straight_max_robot_yaw", m_straightMaxRobotYaw, m_straightMaxRobotYaw);
00152 privateNh.param("straight_max_path_dev", m_straightMaxPathDev, m_straightMaxPathDev);
00153 privateNh.param("straight_threshold", m_straightThreshold, m_straightThreshold);
00154 privateNh.param("straight_offset", m_straightOffset, m_straightOffset);
00155
00156 m_stepFactor = ((m_maxStepFreq - m_minStepFreq) * m_stepFreq + m_minStepFreq) / m_maxStepFreq;
00157 ROS_INFO("Using step factor of %4.2f",m_stepFactor);
00158
00159 if(m_useVelocityController) {
00160 ROS_INFO("Using velocity controller");
00161 m_velPub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00162 } else {
00163 ROS_INFO("Using target pose controller");
00164 m_targetPub = nh.advertise<geometry_msgs::Pose2D>("cmd_pose", 10);
00165 }
00166
00167 m_actionGoalPub = nh.advertise<move_base_msgs::MoveBaseActionGoal>("walk_target/goal", 1);
00168 m_actionPathPub = nh.advertise<nao_msgs::FollowPathActionGoal>("walk_path/goal", 1);
00169
00170
00171
00172 m_simpleGoalSub = nh.subscribe<geometry_msgs::PoseStamped>("walk_target_simple/goal", 1, boost::bind(&PathFollower::goalCB, this, _1));
00173 m_simplePathSub = nh.subscribe<nav_msgs::Path>("walk_path_simple/goal", 1, boost::bind(&PathFollower::pathCB, this, _1));
00174
00175 if(m_useFootContactProtection) {
00176 m_footContactSub = nh.subscribe<std_msgs::Bool>("foot_contact", 1, &PathFollower::footContactCallback, this);
00177 }
00178
00179 m_inhibitWalkClient = nh.serviceClient<std_srvs::Empty>("inhibit_walk");
00180 m_uninhibitWalkClient = nh.serviceClient<std_srvs::Empty>("uninhibit_walk");
00181
00182 m_visPub = privateNh.advertise<geometry_msgs::PoseStamped>("target_pose", 1, true);
00183
00184
00185 m_walkGoalServer.start();
00186 m_walkPathServer.start();
00187 }
00188
00189 PathFollower::~PathFollower(){
00190 std::cerr << "Quitting PathFollower.." << std::endl;
00191
00192 stopWalk();
00193 std::cout << ".. stopWalk() called before quitting" << std::endl;
00194
00195 }
00196
00201 void PathFollower::publishTargetPoseVis(const tf::Stamped<tf::Pose>& targetPose) {
00202 geometry_msgs::PoseStamped targetPoseMsg;
00203 tf::poseStampedTFToMsg(targetPose, targetPoseMsg);
00204 m_visPub.publish(targetPoseMsg);
00205 }
00206
00207 void PathFollower::goalCB(const geometry_msgs::PoseStampedConstPtr& goal) {
00208 ROS_DEBUG("In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
00209 move_base_msgs::MoveBaseActionGoal action_goal;
00210 action_goal.header.stamp = ros::Time::now();
00211 action_goal.goal.target_pose = *goal;
00212 m_actionGoalPub.publish(action_goal);
00213 }
00214
00215 void PathFollower::pathCB(const nav_msgs::PathConstPtr& goal) {
00216 ROS_INFO("Simple Path callback");
00217 ROS_DEBUG("In ROS path callback, wrapping the Path in the action message and re-sending to the server.");
00218 nao_msgs::FollowPathActionGoal action_goal;
00219 action_goal.header = goal->header;
00220 action_goal.goal.path = *goal;
00221 m_actionPathPub.publish(action_goal);
00222 }
00223
00224 void PathFollower::footContactCallback(const std_msgs::BoolConstPtr& contact) {
00225 m_footContact = contact->data;
00226 }
00227
00228 void PathFollower::inhibitJoystick(){
00229 if(!m_isJoystickInhibited) {
00230 std_srvs::Empty e;
00231 if(m_inhibitWalkClient.call(e)) {
00232 ROS_INFO("Joystick inhibited");
00233 m_isJoystickInhibited = true;
00234 } else {
00235 ROS_WARN_ONCE("Could not inhibit joystick walk");
00236 }
00237 }
00238 }
00239
00240
00241 bool hasOrientation(const geometry_msgs::Pose & pose)
00242 {
00243 double eps = 1e-5;
00244 if ( fabs(pose.orientation.x) < eps && fabs(pose.orientation.y) < eps && fabs(pose.orientation.z) < eps && fabs(pose.orientation.w) < eps )
00245 return false;
00246 geometry_msgs::Quaternion q = pose.orientation;
00247 if ( fabs(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w -1 ) > eps)
00248 return false;
00249 return true;
00250
00251 }
00252
00253 bool PathFollower::getRobotPose( tf::StampedTransform & globalToBase, const std::string & global_frame_id)
00254 {
00255 try
00256 {
00257
00258
00259 m_tfListener.lookupTransform(global_frame_id, m_baseFrameId, ros::Time(), globalToBase);
00260
00261 }
00262 catch(const tf::TransformException& e)
00263 {
00264 ROS_WARN("Failed to obtain tf to base (%s)", e.what());
00265 return false;
00266 }
00267
00268 globalToBase.getOrigin().setZ(0.0);
00269 double roll, pitch, yaw;
00270 globalToBase.getBasis().getRPY(roll, pitch, yaw);
00271 globalToBase.setRotation(tf::createQuaternionFromYaw(yaw));
00272 return true;
00273 }
00274
00275 double poseDist(const tf::Pose& p1, const tf::Pose& p2)
00276 {
00277 return (p1.getOrigin() - p2.getOrigin()).length();
00278 }
00279
00280 double poseDist(const geometry_msgs::Pose& p1, const geometry_msgs::Pose& p2){
00281 tf::Vector3 p1_tf, p2_tf;
00282 tf::pointMsgToTF(p1.position, p1_tf);
00283 tf::pointMsgToTF(p2.position, p2_tf);
00284
00285 return (p1_tf - p2_tf).length();
00286 }
00287
00288 void print_transform(const tf::Transform & t)
00289 {
00290 geometry_msgs::Pose m;
00291 tf::poseTFToMsg(t, m);
00292 std::cout << m;
00293 }
00294
00295 double getYawBetween(const geometry_msgs::Pose& p1, const geometry_msgs::Pose& p2){
00296 tf::Vector3 o1, o2;
00297 tf::pointMsgToTF(p1.position, o1);
00298 tf::pointMsgToTF(p2.position, o2);
00299
00300 return std::atan2(o2.getY() - o1.getY(), o2.getX() - o1.getX());
00301 }
00302
00303 double getYawBetween(const tf::Transform & p1, const tf::Transform & p2){
00304 tf::Vector3 o1 = p1.getOrigin();
00305 tf::Vector3 o2 = p2.getOrigin();
00306 return std::atan2( o2.getY() - o1.getY(), o2.getX() - o1.getX());
00307 }
00308
00309 tf::Quaternion getOrientationBetween(const tf::Transform & p1, const tf::Transform & p2)
00310 {
00311 double yaw = getYawBetween(p1, p2);
00312 return (tf::createQuaternionFromYaw(yaw));
00313 }
00314
00315 tf::Quaternion getOrientationBetween(const geometry_msgs::Pose& p1, const geometry_msgs::Pose& p2)
00316 {
00317 double yaw = getYawBetween(p1, p2);
00318 return (tf::createQuaternionFromYaw(yaw));
00319 }
00320
00321
00322 typedef std::vector< geometry_msgs::PoseStamped>::const_iterator PathIterator;
00323
00324 double moveAlongPathByDistance( const PathIterator & start, PathIterator & end, double targetDistance)
00325 {
00326 PathIterator iter = start;
00327 double dist = 0.0;
00328 while(iter+1 != end ){
00329
00330 double d = poseDist(iter->pose, (iter+1)->pose);
00331 if (dist + d > targetDistance )
00332 break;
00333 dist += d;
00334 ++iter;
00335 }
00336 end = iter;
00337 return dist;
00338 }
00339
00340
00341 bool PathFollower::getNextTarget(const nav_msgs::Path& path, const tf::Pose& robotPose, const std::vector<geometry_msgs::PoseStamped>::const_iterator & currentPathPoseIt, tf::Stamped<tf::Transform> & targetPose, std::vector< geometry_msgs::PoseStamped>::const_iterator & targetPathPoseIt)
00342 {
00343
00344
00345 if( path.poses.empty() || currentPathPoseIt == path.poses.end() )
00346 {
00347 ROS_ERROR("Path does not have successors for currentPathPoseIt (i.e. currentPathPoseIt pointing to past-the-end or is empty)");
00348 return true;
00349
00350 }
00351
00352
00353
00354 if( currentPathPoseIt+1 == path.poses.end() )
00355 {
00356
00357
00358 ROS_DEBUG("Goal almost reached! Keeping targetPose. ");
00359
00360
00361 if (!hasOrientation(targetPathPoseIt->pose)){
00362
00363 targetPose.setRotation(robotPose.getRotation());
00364 }
00365 return true;
00366 }
00367
00368
00369
00370
00371
00372
00373
00374
00375 m_straight = false;
00376 std::vector< geometry_msgs::PoseStamped>::const_iterator farIter = currentPathPoseIt;
00377 tf::Stamped<tf::Transform> currentPose, nearPose, farPose;
00378 tf::poseStampedMsgToTF(*(currentPathPoseIt), currentPose);
00379 double straightDist = 0.0;
00380 bool nearEnd = true;
00381 while(farIter+1 != path.poses.end()){
00382 tf::poseStampedMsgToTF(*farIter, farPose);
00383 if(straightDist <= m_straightThreshold/4)
00384 tf::poseStampedMsgToTF(*farIter, nearPose);
00385 straightDist += poseDist(farIter->pose, (farIter+1)->pose);
00386 if(straightDist > m_straightThreshold){
00387 nearEnd = false;
00388 break;
00389 }
00390 ++farIter;
00391 }
00392
00393 if(!nearEnd){
00394 double robotYaw = tf::getYaw(robotPose.getRotation());
00395 double robotToFar = getYawBetween(robotPose, farPose);
00396 double currentToNear = getYawBetween(currentPose, nearPose);
00397 double currentToFar = getYawBetween(currentPose, farPose);
00398 bool robot_on_straight = (poseDist(robotPose, currentPose) < m_straightMaxRobotDev);
00399 bool path_is_straight = std::abs(angles::shortest_angular_distance(currentToNear,currentToFar)) < m_straightMaxPathDev;
00400 bool robot_faces_straight = std::abs(angles::shortest_angular_distance(robotYaw,robotToFar)) < m_straightMaxRobotYaw;
00401
00402 m_straight = (robot_on_straight && path_is_straight && robot_faces_straight);
00403
00404 if(m_straight)
00405 ROS_DEBUG("Robot is walking on a straight path.");
00406
00407 }
00408
00409
00410
00411 std::vector< geometry_msgs::PoseStamped>::const_iterator iter = currentPathPoseIt+1;
00412 tf::Stamped<tf::Transform> tfPose;
00413 tf::poseStampedMsgToTF( *iter, tfPose);
00414 double dist = poseDist( robotPose, tfPose);
00415 bool targetIsEndOfPath = true;
00416 while(iter+1 != path.poses.end() )
00417 {
00418 double d = poseDist(iter->pose, (iter+1)->pose);
00419 if (dist + d > m_pathNextTargetDistance )
00420 {
00421 targetIsEndOfPath = false;
00422 break;
00423 }
00424 dist += d;
00425 ++iter;
00426 }
00427
00428 targetPathPoseIt = iter;
00429 tf::poseStampedMsgToTF(*iter, targetPose);
00430
00431
00432
00433 if ( !hasOrientation (iter->pose) )
00434 {
00435
00436 tf::Quaternion orientation;
00437 assert(iter != currentPathPoseIt);
00438 if (targetIsEndOfPath)
00439 {
00440 orientation = getOrientationBetween( (iter-1)->pose, targetPathPoseIt->pose);
00441 }
00442 else
00443 {
00444
00445 double yaw = getYawBetween(targetPathPoseIt->pose, (targetPathPoseIt+1)->pose);
00446 if (targetPathPoseIt-1 != path.poses.begin() && targetPathPoseIt + 2 != path.poses.end() ){
00447 double yaw1 = getYawBetween((targetPathPoseIt-2)->pose, targetPathPoseIt->pose);
00448 double yaw2 = getYawBetween(targetPathPoseIt->pose, (targetPathPoseIt+2)->pose);
00449 yaw = atan2( sin(yaw1)+sin(yaw2), cos(yaw1) + cos(yaw2) );
00450 }
00451 orientation = tf::createQuaternionFromYaw(yaw);
00452
00453
00454 }
00455 targetPose.setRotation(orientation);
00456
00457
00458 }
00459
00460 return targetIsEndOfPath;
00461
00462 }
00463
00464
00465 void PathFollower::pathActionCB(const nao_msgs::FollowPathGoalConstPtr &goal){
00466 ROS_INFO("path action starting...");
00467
00468 nav_msgs::Path path = goal->path;
00469 nao_msgs::FollowPathFeedback feedback;
00470
00471 if( path.poses.empty() )
00472 {
00473 ROS_INFO("Stop requested by sending empty path.");
00474 stopWalk();
00475 m_walkPathServer.setSucceeded(nao_msgs::FollowPathResult(),"Stop succeeed");
00476 return;
00477 }
00478
00479 ros::Rate r(m_controllerFreq);
00480
00481 ros::Time lastTfSuccessTime = ros::Time::now();
00482 tf::StampedTransform globalToBase;
00483 double tfLookupTimeThresh = 1.0;
00484 std::string global_frame_id = path.header.frame_id;
00485 while (! getRobotPose(globalToBase, global_frame_id) )
00486 {
00487 if ( (ros::Time::now() - lastTfSuccessTime ).toSec() > tfLookupTimeThresh )
00488 {
00489 ROS_ERROR("Could not get robot pose. Stopping robot");
00490 stopWalk();
00491 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(),"Aborted");
00492 return;
00493 }
00494 else
00495 {
00496 r.sleep();
00497 continue;
00498 }
00499 }
00500
00501 lastTfSuccessTime = ros::Time::now();
00502
00503
00504 std::vector< geometry_msgs::PoseStamped>::const_iterator currentPathPoseIt, targetPathPoseIt;
00505 currentPathPoseIt = path.poses.begin();
00506 targetPathPoseIt = currentPathPoseIt;
00507
00508 tf::Stamped<tf::Transform> targetPose;
00509
00510 tf::poseStampedMsgToTF( *currentPathPoseIt, targetPose);
00511
00512 if (poseDist(targetPose, globalToBase)> m_pathStartMaxDistance)
00513 {
00514 ROS_ERROR("Robot is too far away from start of plan. aborting");
00515 stopWalk();
00516 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(),"Aborted");
00517 return;
00518 }
00519
00520
00521 bool targetIsEndOfPath = getNextTarget(path, globalToBase, currentPathPoseIt, targetPose, targetPathPoseIt );
00522 publishTargetPoseVis(targetPose);
00523 inhibitJoystick();
00524
00525 while(ros::ok()){
00526 if (! getRobotPose(globalToBase, global_frame_id) )
00527 {
00528 if ( (ros::Time::now() - lastTfSuccessTime ).toSec() > tfLookupTimeThresh )
00529 {
00530 ROS_ERROR("Could not get robot pose. Stopping robot");
00531 stopWalk();
00532 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(),"Aborted");
00533 return;
00534 }
00535 else
00536 {
00537 r.sleep();
00538 continue;
00539 }
00540 }
00541
00542 lastTfSuccessTime = ros::Time::now();
00543 double dt = (lastTfSuccessTime - globalToBase.stamp_).toSec();
00544 if ( dt > tfLookupTimeThresh )
00545 {
00546 ROS_WARN("TF transforms are behind current clock by %4.2f", dt);
00547
00548 }
00549
00550 if (m_walkPathServer.isPreemptRequested()){
00551 if(m_walkPathServer.isNewGoalAvailable()){
00552 ROS_INFO("walk_path ActionServer: new goal available");
00553 nao_msgs::FollowPathGoal newGoal = *m_walkPathServer.acceptNewGoal();
00554 path = newGoal.path;
00555
00556 if( path.poses.empty() )
00557 {
00558 ROS_INFO("Stop requested by sending empty path.");
00559 stopWalk();
00560 m_walkPathServer.setSucceeded(nao_msgs::FollowPathResult(),"Stop succeeed");
00561 return;
00562 }
00563
00564
00565 currentPathPoseIt = path.poses.begin();
00566 tf::poseStampedMsgToTF( *currentPathPoseIt, targetPose);
00567 if (poseDist(targetPose, globalToBase)> m_pathStartMaxDistance )
00568 {
00569 ROS_ERROR("Robot is too far away from start of plan. aborting");
00570 stopWalk();
00571 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(),"Aborted");
00572 return;
00573 }
00574
00575
00576 targetIsEndOfPath = getNextTarget(path, globalToBase, currentPathPoseIt, targetPose, targetPathPoseIt );
00577 publishTargetPoseVis(targetPose);
00578 inhibitJoystick();
00579
00580 } else {
00581 ROS_INFO("walk_path ActionServer preempted");
00582
00583 stopWalk();
00584
00585 m_walkPathServer.setPreempted();
00586 return;
00587 }
00588 }
00589
00590 if(m_useFootContactProtection && !m_footContact) {
00591 ROS_WARN("Lost foot contact, abort walk");
00592 stopWalk();
00593 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(), "Aborting on the goal because the robot lost foot contact with the ground");
00594 return;
00595 }
00596
00597
00598
00599
00600
00601
00602
00603
00604
00605
00606
00607 double roll, pitch, yaw;
00608 tf::Transform relTarget = globalToBase.inverseTimes(targetPose);
00609 relTarget.getBasis().getRPY(roll, pitch, yaw);
00610
00611
00612
00613 if (targetIsEndOfPath && relTarget.getOrigin().length()< m_targetDistThres && std::abs(yaw) < m_targetAngThres){
00614 ROS_INFO("Target (%f %f %F) reached", targetPose.getOrigin().x(), targetPose.getOrigin().y(),
00615 tf::getYaw(targetPose.getRotation()));
00616
00617 stopWalk();
00618
00619 m_walkPathServer.setSucceeded(nao_msgs::FollowPathResult(), "Target reached");
00620 return;
00621 } else if (!targetIsEndOfPath && relTarget.getOrigin().length()< m_waypointDistThres && std::abs(yaw) < m_waypointAngThres){
00622
00623 currentPathPoseIt = targetPathPoseIt;
00624
00625 targetIsEndOfPath = getNextTarget(path, globalToBase, currentPathPoseIt, targetPose, targetPathPoseIt );
00626 publishTargetPoseVis(targetPose);
00627
00628 relTarget = globalToBase.inverseTimes(targetPose);
00629 }
00630
00631
00632
00633
00634 tf::Transform relTargetStraight = relTarget;
00635 if(m_straight){
00636 std::vector< geometry_msgs::PoseStamped>::const_iterator targetIter = currentPathPoseIt;
00637 tf::Stamped<tf::Transform> targetPose, iterPose;
00638 double straightDist = 0.0;
00639 while(targetIter+1 != path.poses.end()){
00640 tf::poseStampedMsgToTF(*targetIter, targetPose);
00641 tf::poseStampedMsgToTF(*(targetIter+1), iterPose);
00642 straightDist += poseDist(targetPose, iterPose);
00643 if(straightDist > m_straightOffset)
00644 break;
00645 ++targetIter;
00646 }
00647 tf::Stamped<tf::Transform> straightTargetPose;
00648 tf::poseStampedMsgToTF(*targetIter, straightTargetPose);
00649 relTargetStraight = globalToBase.inverseTimes(straightTargetPose);
00650 relTargetStraight.setRotation(relTarget.getRotation());
00651 }
00652 if(m_useVelocityController) {
00653 setVelocity(relTargetStraight);
00654 } else {
00655 geometry_msgs::Pose2D target;
00656 target.x = relTargetStraight.getOrigin().x();
00657 target.y = relTargetStraight.getOrigin().y();
00658 target.theta = tf::getYaw(relTargetStraight.getRotation());
00659
00660 m_targetPub.publish(target);
00661 }
00662
00663 r.sleep();
00664
00665 if(r.cycleTime() > ros::Duration(1 / m_controllerFreq))
00666 ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", m_controllerFreq, r.cycleTime().toSec());
00667
00668 }
00669
00670
00671
00672
00673 stopWalk();
00674 m_walkPathServer.setAborted(nao_msgs::FollowPathResult(), "Aborting on the goal because the node has been killed");
00675
00676
00677
00678 std::cout << ("... path action ending") << std::endl;
00679 }
00680
00681
00682 void PathFollower::goalActionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal){
00683 tf::Stamped<tf::Transform> targetPose;
00684 tf::poseStampedMsgToTF(goal->target_pose, targetPose);
00685
00686 publishTargetPoseVis(targetPose);
00687
00688 ros::Rate r(m_controllerFreq);
00689 inhibitJoystick();
00690
00691
00692 while(nh.ok()){
00693 if (m_walkGoalServer.isPreemptRequested()){
00694 if(m_walkGoalServer.isNewGoalAvailable()){
00695 ROS_INFO("walk_target ActionServer: new goal available");
00696 move_base_msgs::MoveBaseGoal newGoal = *m_walkGoalServer.acceptNewGoal();
00697 tf::poseStampedMsgToTF(newGoal.target_pose, targetPose);
00698 publishTargetPoseVis(targetPose);
00699 inhibitJoystick();
00700
00701 } else {
00702 ROS_INFO("walk_target ActionServer preempted");
00703
00704 stopWalk();
00705
00706 m_walkGoalServer.setPreempted();
00707 return;
00708 }
00709 }
00710
00711 if(m_useFootContactProtection && !m_footContact) {
00712 ROS_WARN("Lost foot contact, abort walk");
00713 stopWalk();
00714 m_walkGoalServer.setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the robot lost foot contact with the ground");
00715 return;
00716 }
00717
00718
00719
00720 tf::StampedTransform globalToBase;
00721 try
00722 {
00723
00724
00725 m_tfListener.lookupTransform(targetPose.frame_id_, m_baseFrameId, ros::Time(), globalToBase);
00726 }
00727 catch(const tf::TransformException& e)
00728 {
00729 ROS_WARN("Failed to obtain tf to base (%s)", e.what());
00730 r.sleep();
00731 continue;
00732 }
00733
00734 globalToBase.getOrigin().setZ(0.0);
00735 double roll, pitch, yaw;
00736 globalToBase.getBasis().getRPY(roll, pitch, yaw);
00737 globalToBase.setRotation(tf::createQuaternionFromYaw(yaw));
00738
00739 move_base_msgs::MoveBaseFeedback feedback;
00740 feedback.base_position.header.stamp = globalToBase.stamp_;
00741 feedback.base_position.header.frame_id = globalToBase.frame_id_;
00742 tf::poseTFToMsg(globalToBase, feedback.base_position.pose);
00743 m_walkGoalServer.publishFeedback(feedback);
00744
00745
00746 tf::Transform relTarget = globalToBase.inverseTimes(targetPose);
00747 relTarget.getBasis().getRPY(roll, pitch, yaw);
00748
00749
00750 if (relTarget.getOrigin().length()< m_targetDistThres && std::abs(yaw) < m_targetAngThres){
00751 ROS_INFO("Target (%f %f %F) reached", targetPose.getOrigin().x(), targetPose.getOrigin().y(),
00752 tf::getYaw(targetPose.getRotation()));
00753
00754 stopWalk();
00755
00756 m_walkGoalServer.setSucceeded(move_base_msgs::MoveBaseResult(), "Target reached");
00757 return;
00758 } else {
00759 if(m_useVelocityController) {
00760 setVelocity(relTarget);
00761 } else {
00762 geometry_msgs::Pose2D target;
00763
00764 if (relTarget.getOrigin().length() > 0.2){
00765 relTarget.setOrigin(0.2* relTarget.getOrigin().normalized());
00766 yaw = atan2(relTarget.getOrigin().y(), relTarget.getOrigin().x());
00767 }
00768 target.x = relTarget.getOrigin().x();
00769 target.y = relTarget.getOrigin().y();
00770 target.theta = yaw;
00771
00772 m_targetPub.publish(target);
00773 }
00774 }
00775
00776 r.sleep();
00777
00778 if(r.cycleTime() > ros::Duration(1 / m_controllerFreq))
00779 ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", m_controllerFreq, r.cycleTime().toSec());
00780
00781 }
00782
00783
00784 stopWalk();
00785 m_walkGoalServer.setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
00786
00787 }
00788
00792 void PathFollower::stopWalk(){
00793 std_srvs::Empty::Request req;
00794 std_srvs::Empty::Response resp;
00795 if (!ros::service::call("stop_walk_srv", req, resp)){
00796 if(m_useVelocityController) {
00797 ROS_WARN("Call to stop_walk_srv Service failed, falling back to velocity=0,0,0");
00798 geometry_msgs::Twist twist;
00799 twist.linear.x = 0.0;
00800 twist.linear.y = 0.0;
00801 twist.angular.z = 0.0;
00802 m_velPub.publish(twist);
00803 }
00804 else
00805 {
00806 ROS_WARN("Call to stop_walk_srv Service failed, falling back to target=0,0,0");
00807 geometry_msgs::Pose2D target;
00808 target.x = 0.0;
00809 target.y = 0.0;
00810 target.theta = 0.0;
00811 m_targetPub.publish(target);
00812 }
00813 }
00814 if(m_isJoystickInhibited) {
00815 std_srvs::Empty e;
00816 if(m_uninhibitWalkClient.call(e)) {
00817 ROS_INFO("Joystick uninhibited");
00818 m_isJoystickInhibited = false;
00819 } else {
00820 ROS_WARN("Could not uninhibit joystick walk");
00821 }
00822 }
00823 }
00824
00841 void PathFollower::setVelocity(const tf::Transform& relTarget) {
00842 double dx, dy, yaw;
00843 bool rotateOnSpot;
00844 const double dist = relTarget.getOrigin().length();
00845 if(dist > m_thresholdFar) {
00846
00847 yaw = atan2(relTarget.getOrigin().y(), relTarget.getOrigin().x());
00848 rotateOnSpot = (std::abs(yaw) > m_thresholdRotate);
00849 } else {
00850
00851 yaw = tf::getYaw(relTarget.getRotation());
00852 rotateOnSpot = (std::abs(yaw) > m_thresholdRotate);
00853 if(dist < m_targetDistThres && std::abs(yaw) < m_targetAngThres) {
00854 geometry_msgs::Twist twist;
00855 twist.linear.x = 0.0;
00856 twist.linear.y = 0.0;
00857 twist.angular.z = 0.0;
00858 m_velPub.publish(twist);
00859 return;
00860 }
00861 }
00862
00863
00864 yaw = angles::normalize_angle(yaw);
00865
00866
00867 const double dampXY = std::min(dist / m_thresholdDampXY, 1.0);
00868 const double dampYaw = std::min(std::abs(yaw) / m_thresholdDampYaw, 1.0);
00869
00870 if(rotateOnSpot) {
00871 dx = 0.0;
00872 dy = 0.0;
00873 } else {
00874 dx = relTarget.getOrigin().x();
00875 dy = relTarget.getOrigin().y();
00876 }
00877
00878 const double times[] = {
00879 std::abs(dx) / ((dampXY * m_maxVelFractionX) * m_maxVelXY * m_stepFactor),
00880 std::abs(dy) / ((dampXY * m_maxVelFractionY) * m_maxVelXY * m_stepFactor),
00881 std::abs(yaw) / ((dampYaw * m_maxVelFractionYaw) * m_maxVelYaw * m_stepFactor),
00882 1. / m_controllerFreq
00883 };
00884 const double maxtime = *std::max_element(times, times + 4);
00885
00886 geometry_msgs::Twist twist;
00887 twist.linear.x = dx / (maxtime * m_maxVelXY * m_stepFactor);
00888 twist.linear.y = dy / (maxtime * m_maxVelXY * m_stepFactor);
00889 twist.angular.z = yaw / (maxtime * m_maxVelYaw * m_stepFactor);
00890
00891 ROS_DEBUG("setVelocity: target %f %f %f --> velocity %f %f %f",
00892 relTarget.getOrigin().x(), relTarget.getOrigin().y(), yaw,
00893 twist.linear.x, twist.linear.y, twist.angular.z);
00894 m_velPub.publish(twist);
00895 }
00896
00897 int main(int argc, char** argv){
00898 ros::init(argc, argv, "nao_path_follower");
00899 PathFollower follower;
00900
00901 ros::spin();
00902
00903 return 0;
00904 }
00905
00906