$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/footstep_planner/src/FootstepNavigation.cpp $ 00002 // SVN $Id: FootstepNavigation.cpp 3979 2013-02-26 14:13:46Z garimort@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * A footstep planner for humanoid robots 00006 * 00007 * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg 00008 * http://www.ros.org/wiki/footstep_planner 00009 * 00010 * 00011 * This program is free software: you can redistribute it and/or modify 00012 * it under the terms of the GNU General Public License as published by 00013 * the Free Software Foundation, version 3. 00014 * 00015 * This program is distributed in the hope that it will be useful, 00016 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00017 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00018 * GNU General Public License for more details. 00019 * 00020 * You should have received a copy of the GNU General Public License 00021 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00022 */ 00023 00024 #include <footstep_planner/FootstepNavigation.h> 00025 00026 00027 namespace footstep_planner 00028 { 00029 FootstepNavigation::FootstepNavigation() 00030 : ivIdFootRight("/r_sole"), 00031 ivIdFootLeft("/l_sole"), 00032 ivIdMapFrame("map"), 00033 ivExecutingFootsteps(false), 00034 ivFootstepsExecution("footsteps_execution", true), 00035 ivExecutionShift(2), 00036 ivControlStepIdx(-1), 00037 ivResetStepIdx(0) 00038 { 00039 // private NodeHandle for parameters and private messages (debug / info) 00040 ros::NodeHandle nh_private("~"); 00041 ros::NodeHandle nh_public; 00042 00043 // service 00044 ivFootstepSrv = nh_public.serviceClient<humanoid_nav_msgs::StepTargetService>( 00045 "footstep_srv"); 00046 ivClipFootstepSrv = nh_public.serviceClient<humanoid_nav_msgs::ClipFootstep>( 00047 "clip_footstep_srv"); 00048 00049 // subscribers 00050 ivGridMapSub = nh_public.subscribe<nav_msgs::OccupancyGrid>( 00051 "map", 1, &FootstepNavigation::mapCallback, this); 00052 ivGoalPoseSub = nh_public.subscribe<geometry_msgs::PoseStamped>( 00053 "goal", 1, &FootstepNavigation::goalPoseCallback, this); 00054 00055 // read parameters from config file: 00056 nh_private.param("rfoot_frame_id", ivIdFootRight, ivIdFootRight); 00057 nh_private.param("lfoot_frame_id", ivIdFootLeft, ivIdFootLeft); 00058 00059 nh_private.param("accuracy/footstep/x", ivAccuracyX, 0.005); 00060 nh_private.param("accuracy/footstep/y", ivAccuracyY, 0.005); 00061 nh_private.param("accuracy/footstep/theta", ivAccuracyTheta, 0.05); 00062 00063 nh_private.param("accuracy/cell_size", ivCellSize, 0.005); 00064 nh_private.param("accuracy/num_angle_bins", ivNumAngleBins, 128); 00065 00066 nh_private.param("forward_search", ivForwardSearch, false); 00067 00068 nh_private.param("feedback_frequency", ivFeedbackFrequency, 5.0); 00069 nh_private.param("safe_execution", ivSafeExecution, true); 00070 00071 // check if each footstep can be performed by the NAO robot 00072 XmlRpc::XmlRpcValue footsteps_x; 00073 XmlRpc::XmlRpcValue footsteps_y; 00074 XmlRpc::XmlRpcValue footsteps_theta; 00075 ros::ServiceClient footstep_clip_srv = nh_public.serviceClient< 00076 humanoid_nav_msgs::ClipFootstep>("clip_footstep_srv"); 00077 humanoid_nav_msgs::ClipFootstep performable_step; 00078 humanoid_nav_msgs::StepTarget step; 00079 // read the footstep parameters 00080 nh_private.getParam("footsteps/x", footsteps_x); 00081 nh_private.getParam("footsteps/y", footsteps_y); 00082 nh_private.getParam("footsteps/theta", footsteps_theta); 00083 if (footsteps_x.getType() != XmlRpc::XmlRpcValue::TypeArray) 00084 ROS_ERROR("Error reading footsteps/x from config file."); 00085 if (footsteps_y.getType() != XmlRpc::XmlRpcValue::TypeArray) 00086 ROS_ERROR("Error reading footsteps/y from config file."); 00087 if (footsteps_theta.getType() != XmlRpc::XmlRpcValue::TypeArray) 00088 ROS_ERROR("Error reading footsteps/theta from config file."); 00089 // check each footstep 00090 for(int i=0; i < footsteps_x.size(); i++) 00091 { 00092 double x = (double) footsteps_x[i]; 00093 double y = (double) footsteps_y[i]; 00094 double theta = (double) footsteps_theta[i]; 00095 00096 step.pose.x = x; 00097 step.pose.y = y; 00098 step.pose.theta = theta; 00099 step.leg = humanoid_nav_msgs::StepTarget::left; 00100 00101 performable_step.request.step = step; 00102 footstep_clip_srv.call(performable_step); 00103 00104 if (fabs(step.pose.x - performable_step.response.step.pose.x) > 00105 FLOAT_CMP_THR || 00106 fabs(step.pose.y - performable_step.response.step.pose.y) > 00107 FLOAT_CMP_THR || 00108 fabs(angles::shortest_angular_distance( 00109 step.pose.theta, performable_step.response.step.pose.theta)) > 00110 FLOAT_CMP_THR) 00111 { 00112 ROS_ERROR("Step (%f, %f, %f) cannot be performed by the NAO " 00113 "robot. Exit!", x, y, theta); 00114 exit(2); 00115 } 00116 } 00117 00118 // TODO: read this from config file 00119 // create the polygon that defines the executable range of a single step 00120 // this range is valid for all thetas in [-0.3, 0.3] 00121 float x = 0.0; 00122 float y = 0.15; 00123 ivStepRange.push_back(std::pair<float, float>(x, y)); 00124 x = 0.01; 00125 y = 0.15; 00126 ivStepRange.push_back(std::pair<float, float>(x, y)); 00127 x = 0.02; 00128 y = 0.15; 00129 ivStepRange.push_back(std::pair<float, float>(x, y)); 00130 x = 0.03; 00131 y = 0.14; 00132 ivStepRange.push_back(std::pair<float, float>(x, y)); 00133 x = 0.05; 00134 y = 0.13; 00135 ivStepRange.push_back(std::pair<float, float>(x, y)); 00136 x = 0.06; 00137 y = 0.13; 00138 ivStepRange.push_back(std::pair<float, float>(x, y)); 00139 x = 0.07; 00140 y = 0.12; 00141 ivStepRange.push_back(std::pair<float, float>(x, y)); 00142 x = 0.07; 00143 y = 0.09; 00144 ivStepRange.push_back(std::pair<float, float>(x, y)); 00145 x = -0.03; 00146 y = 0.09; 00147 ivStepRange.push_back(std::pair<float, float>(x, y)); 00148 x = -0.03; 00149 y = 0.13; 00150 ivStepRange.push_back(std::pair<float, float>(x, y)); 00151 x = -0.02; 00152 y = 0.14; 00153 ivStepRange.push_back(std::pair<float, float>(x, y)); 00154 x = -0.02; 00155 y = 0.14; 00156 ivStepRange.push_back(std::pair<float, float>(x, y)); 00157 x = -0.01; 00158 y = 0.15; 00159 ivStepRange.push_back(std::pair<float, float>(x, y)); 00160 // first point has to be included at the end of the list again 00161 x = 0.0; 00162 y = 0.15; 00163 ivStepRange.push_back(std::pair<float, float>(x, y)); 00164 } 00165 00166 00167 FootstepNavigation::~FootstepNavigation() 00168 {} 00169 00170 00171 bool 00172 FootstepNavigation::plan() 00173 { 00174 if (!updateStart()) 00175 { 00176 ROS_ERROR("Start pose not accessible!"); 00177 return false; 00178 } 00179 00180 if (ivPlanner.plan()) 00181 { 00182 startExecution(); 00183 return true; 00184 } 00185 // path planning unsuccessful 00186 return false; 00187 } 00188 00189 00190 bool 00191 FootstepNavigation::replan() 00192 { 00193 if (!updateStart()) 00194 { 00195 ROS_ERROR("Start pose not accessible!"); 00196 return false; 00197 } 00198 00199 bool path_existed = ivPlanner.pathExists(); 00200 00201 // calculate path by replanning (if no planning information exists 00202 // this call is equal to ivPlanner.plan()) 00203 if (ivPlanner.replan()) 00204 { 00205 startExecution(); 00206 return true; 00207 } 00208 else if (path_existed) 00209 { 00210 ROS_INFO("Replanning unsuccessful. Reseting previous planning " 00211 "information."); 00212 if (ivPlanner.plan()) 00213 { 00214 startExecution(); 00215 return true; 00216 } 00217 } 00218 // path planning unsuccessful 00219 ivExecutingFootsteps = false; 00220 return false; 00221 } 00222 00223 00224 void 00225 FootstepNavigation::startExecution() 00226 { 00227 if (ivSafeExecution) 00228 { 00229 ivFootstepExecutionPtr.reset( 00230 new boost::thread( 00231 boost::bind(&FootstepNavigation::executeFootsteps, this))); 00232 } 00233 else 00234 { 00235 // ALTERNATIVE: 00236 executeFootstepsFast(); 00237 } 00238 } 00239 00240 00241 void 00242 FootstepNavigation::executeFootsteps() 00243 { 00244 if (ivPlanner.getPathSize() <= 1) 00245 return; 00246 00247 // lock this thread 00248 ivExecutingFootsteps = true; 00249 00250 ROS_INFO("Start walking towards the goal."); 00251 00252 humanoid_nav_msgs::StepTarget step; 00253 humanoid_nav_msgs::StepTargetService step_srv; 00254 00255 tf::Transform from; 00256 std::string support_foot_id; 00257 State from_planned; 00258 00259 // calculate and perform relative footsteps until goal is reached 00260 state_iter_t to_planned = ivPlanner.getPathBegin(); 00261 if (to_planned == ivPlanner.getPathEnd()) 00262 { 00263 ROS_ERROR("No plan available. Return."); 00264 return; 00265 } 00266 00267 from_planned = *to_planned; 00268 to_planned++; 00269 while (to_planned != ivPlanner.getPathEnd()) 00270 { 00271 try 00272 { 00273 boost::this_thread::interruption_point(); 00274 } 00275 catch (const boost::thread_interrupted&) 00276 { 00277 // leave this thread 00278 return; 00279 } 00280 00281 if (to_planned->getLeg() == LEFT) 00282 support_foot_id = ivIdFootRight; 00283 else // support_foot = LLEG 00284 support_foot_id = ivIdFootLeft; 00285 // try to get real placement of the support foot 00286 if (getFootTransform(support_foot_id, ivIdMapFrame, ros::Time::now(), 00287 ros::Duration(0.5), from)) 00288 { 00289 // calculate relative step and check if it can be performed 00290 if (getFootstep(from, from_planned, *to_planned, step)) 00291 { 00292 step_srv.request.step = step; 00293 ivFootstepSrv.call(step_srv); 00294 } 00295 // ..if it cannot be performed initialize replanning 00296 else 00297 { 00298 ROS_INFO("Footstep cannot be performed. Replanning necessary."); 00299 00300 replan(); 00301 // leave the thread 00302 return; 00303 } 00304 } 00305 else 00306 { 00307 // if the support foot could not be received wait and try again 00308 ros::Duration(0.5).sleep(); 00309 continue; 00310 } 00311 00312 from_planned = *to_planned; 00313 to_planned++; 00314 } 00315 ROS_INFO("Succeeded walking to the goal.\n"); 00316 00317 // free the lock 00318 ivExecutingFootsteps = false; 00319 } 00320 00321 00322 void 00323 FootstepNavigation::executeFootstepsFast() 00324 { 00325 if (ivPlanner.getPathSize() <= 1) 00326 return; 00327 00328 // lock the planning and execution process 00329 ivExecutingFootsteps = true; 00330 00331 // make sure the action client is connected to the action server 00332 ivFootstepsExecution.waitForServer(); 00333 00334 humanoid_nav_msgs::ExecFootstepsGoal goal; 00335 State support_leg; 00336 if (ivPlanner.getPathBegin()->getLeg() == RIGHT) 00337 support_leg = ivPlanner.getStartFootRight(); 00338 else // leg == LEFT 00339 support_leg = ivPlanner.getStartFootLeft(); 00340 if (getFootstepsFromPath(support_leg, 1, goal.footsteps)) 00341 { 00342 goal.feedback_frequency = ivFeedbackFrequency; 00343 ivControlStepIdx = 0; 00344 ivResetStepIdx = 0; 00345 00346 // start the execution via action; _1, _2 are place holders for 00347 // function arguments (see boost doc) 00348 ivFootstepsExecution.sendGoal( 00349 goal, 00350 boost::bind(&FootstepNavigation::doneCallback, this, _1, _2), 00351 boost::bind(&FootstepNavigation::activeCallback, this), 00352 boost::bind(&FootstepNavigation::feedbackCallback, this, _1)); 00353 } 00354 else 00355 { 00356 // free the lock 00357 ivExecutingFootsteps = false; 00358 00359 replan(); 00360 } 00361 } 00362 00363 00364 void 00365 FootstepNavigation::activeCallback() 00366 { 00367 // lock the execution 00368 ivExecutingFootsteps = true; 00369 00370 ROS_INFO("Start walking towards the goal."); 00371 } 00372 00373 00374 void 00375 FootstepNavigation::doneCallback( 00376 const actionlib::SimpleClientGoalState& state, 00377 const humanoid_nav_msgs::ExecFootstepsResultConstPtr& result) 00378 { 00379 if (state == actionlib::SimpleClientGoalState::SUCCEEDED) 00380 ROS_INFO("Succeeded walking to the goal."); 00381 else if (state == actionlib::SimpleClientGoalState::PREEMPTED) 00382 ROS_INFO("Preempted walking to the goal."); 00383 // TODO: distinct between further states?? 00384 else 00385 ROS_INFO("Failed walking to the goal."); 00386 00387 // free the lock 00388 ivExecutingFootsteps = false; 00389 } 00390 00391 00392 void 00393 FootstepNavigation::feedbackCallback( 00394 const humanoid_nav_msgs::ExecFootstepsFeedbackConstPtr& fb) 00395 { 00396 int executed_steps_idx = fb->executed_footsteps.size() - ivExecutionShift; 00397 // make sure at least one step has been performed 00398 if (executed_steps_idx < 0) 00399 return; 00400 // if the currently executed footstep equals the currently observed one 00401 // everything is ok 00402 if (executed_steps_idx == ivControlStepIdx) 00403 return; 00404 00405 // get planned foot placement 00406 const State& planned = *(ivPlanner.getPathBegin() + ivControlStepIdx + 1 + 00407 ivResetStepIdx); 00408 // get executed foot placement 00409 tf::Transform executed_tf; 00410 std::string foot_id; 00411 if (planned.getLeg() == RIGHT) 00412 foot_id = ivIdFootRight; 00413 else 00414 foot_id = ivIdFootLeft; 00415 00416 if (!getFootTransform(foot_id, ivIdMapFrame, ros::Time::now(), 00417 ros::Duration(0.5), executed_tf)) 00418 { 00419 State executed(executed_tf.getOrigin().x(), executed_tf.getOrigin().y(), 00420 tf::getYaw(executed_tf.getRotation()), planned.getLeg()); 00421 ivFootstepsExecution.cancelGoal(); 00422 humanoid_nav_msgs::ExecFootstepsGoal goal; 00423 // try to reach the calculated path 00424 if (getFootstepsFromPath(executed, executed_steps_idx + ivResetStepIdx, 00425 goal.footsteps)) 00426 { 00427 goal.feedback_frequency = ivFeedbackFrequency; 00428 // adjust the internal counters 00429 ivResetStepIdx += ivControlStepIdx + 1; 00430 ivControlStepIdx = 0; 00431 00432 // restart the footstep execution 00433 ivFootstepsExecution.sendGoal( 00434 goal, 00435 boost::bind(&FootstepNavigation::doneCallback, this, _1, _2), 00436 boost::bind(&FootstepNavigation::activeCallback, this), 00437 boost::bind(&FootstepNavigation::feedbackCallback, this, _1)); 00438 } 00439 // the previously calculated path cannot be reached so we have plan 00440 // a new path 00441 else 00442 { 00443 replan(); 00444 } 00445 } 00446 00447 State executed(executed_tf.getOrigin().x(), executed_tf.getOrigin().y(), 00448 tf::getYaw(executed_tf.getRotation()), planned.getLeg()); 00449 00450 // check if the currently executed footstep is no longer observed (i.e. 00451 // the robot no longer follows its calculated path) 00452 if (executed_steps_idx >= ivControlStepIdx + 2) 00453 { 00454 ivFootstepsExecution.cancelGoal(); 00455 00456 ROS_DEBUG("Footstep execution incorrect."); 00457 00458 humanoid_nav_msgs::ExecFootstepsGoal goal; 00459 // try to reach the calculated path 00460 if (getFootstepsFromPath(executed, executed_steps_idx + ivResetStepIdx, 00461 goal.footsteps)) 00462 { 00463 ROS_INFO("Try to reach calculated path."); 00464 00465 goal.feedback_frequency = ivFeedbackFrequency; 00466 // adjust the internal counters 00467 ivResetStepIdx += ivControlStepIdx + 1; 00468 ivControlStepIdx = 0; 00469 00470 // restart the footstep execution 00471 ivFootstepsExecution.sendGoal( 00472 goal, 00473 boost::bind(&FootstepNavigation::doneCallback, this, _1, _2), 00474 boost::bind(&FootstepNavigation::activeCallback, this), 00475 boost::bind(&FootstepNavigation::feedbackCallback, this, _1)); 00476 } 00477 // the previously calculated path cannot be reached so we have plan 00478 // a new path 00479 else 00480 { 00481 replan(); 00482 } 00483 00484 return; 00485 } 00486 // check the currently observed footstep 00487 else 00488 { 00489 ROS_DEBUG("planned (%f, %f, %f, %i) vs. executed (%f, %f, %f, %i)", 00490 planned.getX(), planned.getY(), planned.getTheta(), 00491 planned.getLeg(), 00492 executed.getX(), executed.getY(), executed.getTheta(), 00493 executed.getLeg()); 00494 00495 // adjust the internal step counters if the footstep has been 00496 // performed correctly; otherwise check in the next iteration if 00497 // the step really has been incorrect 00498 if (performanceValid(planned, executed)) 00499 ivControlStepIdx++; 00500 else 00501 ROS_DEBUG("Invalid step. Wait next step update before declaring" 00502 " step incorrect."); 00503 } 00504 } 00505 00506 00507 void 00508 FootstepNavigation::goalPoseCallback( 00509 const geometry_msgs::PoseStampedConstPtr& goal_pose) 00510 { 00511 // check if the execution is locked 00512 if (ivExecutingFootsteps) 00513 { 00514 ROS_INFO("Already performing a navigation task. Wait until it is " 00515 "finished."); 00516 return; 00517 } 00518 00519 if (setGoal(goal_pose)) 00520 { 00521 // this check enforces a planning from scratch if necessary (dependent on 00522 // planning direction) 00523 if (ivForwardSearch) 00524 replan(); 00525 else 00526 plan(); 00527 } 00528 } 00529 00530 00531 void 00532 FootstepNavigation::mapCallback( 00533 const nav_msgs::OccupancyGridConstPtr& occupancy_map) 00534 { 00535 // stop execution if an execution was performed 00536 if (ivExecutingFootsteps) 00537 { 00538 if (ivSafeExecution) 00539 { 00540 // interrupt the thread and wait until it has finished its execution 00541 ivFootstepExecutionPtr->interrupt(); 00542 ivFootstepExecutionPtr->join(); 00543 } 00544 else 00545 { 00546 ivFootstepsExecution.cancelAllGoals(); 00547 } 00548 } 00549 00550 gridmap_2d::GridMap2DPtr map(new gridmap_2d::GridMap2D(occupancy_map)); 00551 ivIdMapFrame = map->getFrameID(); 00552 00553 // updates the map and starts replanning if necessary 00554 if (ivPlanner.updateMap(map)) 00555 { 00556 // NOTE: instead of planning from scratch and deleting all previously 00557 // collected information one could think of updating the states affected 00558 // from the map change, update these states and start a replanning. 00559 00560 // reset the planner 00561 ivPlanner.reset(); 00562 // calculate a new path 00563 replan(); 00564 } 00565 } 00566 00567 00568 bool 00569 FootstepNavigation::setGoal(const geometry_msgs::PoseStampedConstPtr& goal_pose) 00570 { 00571 return setGoal(goal_pose->pose.position.x, 00572 goal_pose->pose.position.y, 00573 tf::getYaw(goal_pose->pose.orientation)); 00574 } 00575 00576 00577 bool 00578 FootstepNavigation::setGoal(float x, float y, float theta) 00579 { 00580 return ivPlanner.setGoal(x, y, theta); 00581 } 00582 00583 00584 bool 00585 FootstepNavigation::updateStart() 00586 { 00587 ros::Duration(0.5).sleep(); 00588 00589 tf::Transform foot_left, foot_right; 00590 { 00591 // get real placement of the feet 00592 if (!getFootTransform(ivIdFootLeft, ivIdMapFrame, ros::Time::now(), 00593 ros::Duration(0.5), foot_left)) 00594 { 00595 if (ivPlanner.pathExists()) 00596 { 00597 ivExecutingFootsteps = false; 00598 } 00599 return false; 00600 } 00601 if (!getFootTransform(ivIdFootRight, ivIdMapFrame, ros::Time::now(), 00602 ros::Duration(0.5), foot_right)) 00603 { 00604 if (ivPlanner.pathExists()) 00605 { 00606 ivExecutingFootsteps = false; 00607 } 00608 return false; 00609 } 00610 } 00611 State left(foot_left.getOrigin().x(), foot_left.getOrigin().y(), 00612 tf::getYaw(foot_left.getRotation()), LEFT); 00613 State right(foot_right.getOrigin().x(), foot_right.getOrigin().y(), 00614 tf::getYaw(foot_right.getRotation()), RIGHT); 00615 00616 ROS_INFO("Robot standing at (%f, %f, %f, %i) (%f, %f, %f, %i).", 00617 left.getX(), left.getY(), left.getTheta(), left.getLeg(), 00618 right.getX(), right.getY(), right.getTheta(), right.getLeg()); 00619 00620 return ivPlanner.setStart(left, right); 00621 } 00622 00623 00624 bool 00625 FootstepNavigation::getFootstep(const tf::Pose& from, 00626 const State& from_planned, 00627 const State& to, 00628 humanoid_nav_msgs::StepTarget& footstep) 00629 { 00630 // get footstep to reach 'to' from 'from' 00631 tf::Transform step = from.inverse() * 00632 tf::Pose(tf::createQuaternionFromYaw(to.getTheta()), 00633 tf::Point(to.getX(), to.getY(), 0.0)); 00634 00635 // set the footstep 00636 footstep.pose.x = step.getOrigin().x(); 00637 footstep.pose.y = step.getOrigin().y(); 00638 footstep.pose.theta = tf::getYaw(step.getRotation()); 00639 if (to.getLeg() == LEFT) 00640 footstep.leg = humanoid_nav_msgs::StepTarget::left; 00641 else // to.leg == RIGHT 00642 footstep.leg = humanoid_nav_msgs::StepTarget::right; 00643 00644 00645 /* check if the footstep can be performed by the NAO robot ******************/ 00646 00647 // check if the step lies within the executable range 00648 if (performable(footstep)) 00649 { 00650 return true; 00651 } 00652 else 00653 { 00654 // check if there is only a minor divergence between the current support 00655 // foot and the foot placement used during the plannig task: in such a case 00656 // perform the step that has been used during the planning 00657 float step_diff_x = fabs(from.getOrigin().x() - from_planned.getX()); 00658 float step_diff_y = fabs(from.getOrigin().y() - from_planned.getY()); 00659 float step_diff_theta = fabs( 00660 angles::shortest_angular_distance( 00661 tf::getYaw(from.getRotation()), from_planned.getTheta())); 00662 if (step_diff_x < ivAccuracyX && step_diff_y < ivAccuracyY && 00663 step_diff_theta < ivAccuracyTheta) 00664 { 00665 step = tf::Pose(tf::createQuaternionFromYaw(from_planned.getTheta()), 00666 tf::Point(from_planned.getX(), from_planned.getY(), 0.0) 00667 ).inverse() * 00668 tf::Pose(tf::createQuaternionFromYaw(to.getTheta()), 00669 tf::Point(to.getX(), to.getY(), 0.0)); 00670 00671 footstep.pose.x = step.getOrigin().x(); 00672 footstep.pose.y = step.getOrigin().y(); 00673 footstep.pose.theta = tf::getYaw(step.getRotation()); 00674 00675 return true; 00676 } 00677 00678 return false; 00679 } 00680 00681 // // ALTERNATIVE: clip the footstep into the executable range; if nothing was 00682 // // clipped: perform; if too much was clipped: do not perform 00683 // humanoid_nav_msgs::ClipFootstep footstep_clip; 00684 // footstep_clip.request.step = footstep; 00685 // ivClipFootstepSrv.call(footstep_clip); 00686 // 00687 // if (performanceValid(footstep_clip)) 00688 // { 00689 // footstep.pose.x = footstep_clip.response.step.pose.x; 00690 // footstep.pose.y = footstep_clip.response.step.pose.y; 00691 // footstep.pose.theta = footstep_clip.response.step.pose.theta; 00692 // return true; 00693 // } 00694 // else 00695 // { 00696 // return false; 00697 // } 00698 } 00699 00700 00701 bool 00702 FootstepNavigation::getFootstepsFromPath( 00703 const State& current_support_leg, int starting_step_num, 00704 std::vector<humanoid_nav_msgs::StepTarget>& footsteps) 00705 { 00706 humanoid_nav_msgs::StepTarget footstep; 00707 00708 state_iter_t to_planned = ivPlanner.getPathBegin() + starting_step_num - 1; 00709 tf::Pose last(tf::createQuaternionFromYaw(current_support_leg.getTheta()), 00710 tf::Point(current_support_leg.getX(), current_support_leg.getY(), 00711 0.0)); 00712 State from_planned = *to_planned; 00713 to_planned++; 00714 for (; to_planned != ivPlanner.getPathEnd(); to_planned++) 00715 { 00716 if (getFootstep(last, from_planned, *to_planned, footstep)) 00717 { 00718 footsteps.push_back(footstep); 00719 } 00720 else 00721 { 00722 ROS_ERROR("Calculated path cannot be performed!"); 00723 return false; 00724 } 00725 00726 last = tf::Pose(tf::createQuaternionFromYaw(to_planned->getTheta()), 00727 tf::Point(to_planned->getX(), to_planned->getY(), 0.0)); 00728 from_planned = *to_planned; 00729 } 00730 00731 return true; 00732 } 00733 00734 00735 bool 00736 FootstepNavigation::getFootTransform( 00737 const std::string& foot_id, const std::string& world_frame_id, 00738 const ros::Time& time, const ros::Duration& waiting_time, tf::Transform& foot) 00739 { 00740 tf::StampedTransform stamped_foot_transform; 00741 try 00742 { 00743 ivTransformListener.waitForTransform(world_frame_id, foot_id, time, 00744 waiting_time); 00745 ivTransformListener.lookupTransform(world_frame_id, foot_id, time, 00746 stamped_foot_transform); 00747 } 00748 catch (const tf::TransformException& e) 00749 { 00750 ROS_WARN("Failed to obtain FootTransform from tf (%s)", e.what()); 00751 return false; 00752 } 00753 00754 foot.setOrigin(stamped_foot_transform.getOrigin()); 00755 foot.setRotation(stamped_foot_transform.getRotation()); 00756 00757 return true; 00758 } 00759 00760 00761 bool 00762 FootstepNavigation::performanceValid(float a_x, float a_y, float a_theta, 00763 float b_x, float b_y, float b_theta) 00764 { 00765 return (fabs(a_x - b_x) < ivAccuracyX && 00766 fabs(a_y - b_y) < ivAccuracyY && 00767 fabs(angles::shortest_angular_distance(a_theta, b_theta)) < 00768 ivAccuracyTheta); 00769 } 00770 00771 00772 bool 00773 FootstepNavigation::performanceValid( 00774 const humanoid_nav_msgs::ClipFootstep& step) 00775 { 00776 return performanceValid(step.request.step.pose.x, 00777 step.request.step.pose.y, 00778 step.request.step.pose.theta, 00779 step.response.step.pose.x, 00780 step.response.step.pose.y, 00781 step.response.step.pose.theta); 00782 } 00783 00784 00785 bool 00786 FootstepNavigation::performanceValid(const State& planned, 00787 const State& executed) 00788 { 00789 return performanceValid( 00790 planned.getX(), planned.getY(), planned.getTheta(), 00791 executed.getX(), executed.getY(), executed.getTheta()); 00792 } 00793 00794 00795 bool 00796 FootstepNavigation::performable(const humanoid_nav_msgs::StepTarget& footstep) 00797 { 00798 float step_x = footstep.pose.x; 00799 float step_y = footstep.pose.y; 00800 float step_theta = footstep.pose.theta; 00801 00802 if (footstep.leg == humanoid_nav_msgs::StepTarget::right) 00803 { 00804 step_y = -step_y; 00805 step_theta = -step_theta; 00806 } 00807 00808 // TODO: make this configurable 00809 if (fabs(step_theta - 0.3) < FLOAT_CMP_THR || 00810 fabs(step_theta + 0.2) < FLOAT_CMP_THR) 00811 { 00812 ROS_ERROR("angle wrong"); 00813 return false; 00814 } 00815 return performable(step_x, step_y); 00816 } 00817 00818 00819 bool 00820 FootstepNavigation::performable(float step_x, float step_y) 00821 { 00822 int cn = 0; 00823 00824 // loop through all ivStepRange of the polygon 00825 for(unsigned int i = 0; i < ivStepRange.size() - 1; ++i) 00826 { 00827 if ((ivStepRange[i].second <= step_y && 00828 ivStepRange[i + 1].second > step_y) || 00829 (ivStepRange[i].second >= step_y && 00830 ivStepRange[i + 1].second < step_y)) 00831 { 00832 float vt = (float)(step_y - ivStepRange[i].second) / 00833 (ivStepRange[i + 1].second - ivStepRange[i].second); 00834 if (step_x < 00835 ivStepRange[i].first + vt * 00836 (ivStepRange[i + 1].first - ivStepRange[i].first)) 00837 { 00838 ++cn; 00839 } 00840 } 00841 } 00842 return cn & 1; 00843 } 00844 }