FootstepNavigation.cpp
Go to the documentation of this file.
1 /*
2  * A footstep planner for humanoid robots
3  *
4  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
5  * http://www.ros.org/wiki/footstep_planner
6  *
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, version 3.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <http://www.gnu.org/licenses/>.
19  */
20 
22 
23 
24 namespace footstep_planner
25 {
27 : ivIdFootRight("/r_sole"),
28  ivIdFootLeft("/l_sole"),
29  ivIdMapFrame("map"),
30  ivExecutingFootsteps(false),
31  ivFootstepsExecution("footsteps_execution", true),
32  ivExecutionShift(2),
33  ivControlStepIdx(-1),
34  ivResetStepIdx(0)
35 {
36  // private NodeHandle for parameters and private messages (debug / info)
37  ros::NodeHandle nh_private("~");
38  ros::NodeHandle nh_public;
39 
40  // service
42  nh_public.serviceClient<humanoid_nav_msgs::StepTargetService>(
43  "footstep_srv");
45  nh_public.serviceClient<humanoid_nav_msgs::ClipFootstep>(
46  "clip_footstep_srv");
47 
48  // subscribers
49  ivGridMapSub =
50  nh_public.subscribe<nav_msgs::OccupancyGrid>(
51  "map", 1, &FootstepNavigation::mapCallback, this);
53  nh_public.subscribe<geometry_msgs::PoseStamped>(
54  "goal", 1, &FootstepNavigation::goalPoseCallback, this);
55 
56  // read parameters from config file:
57  nh_private.param("rfoot_frame_id", ivIdFootRight, ivIdFootRight);
58  nh_private.param("lfoot_frame_id", ivIdFootLeft, ivIdFootLeft);
59 
60  nh_private.param("accuracy/footstep/x", ivAccuracyX, 0.01);
61  nh_private.param("accuracy/footstep/y", ivAccuracyY, 0.01);
62  nh_private.param("accuracy/footstep/theta", ivAccuracyTheta, 0.1);
63 
64  nh_private.param("accuracy/cell_size", ivCellSize, 0.005);
65  nh_private.param("accuracy/num_angle_bins", ivNumAngleBins, 128);
66 
67  nh_private.param("forward_search", ivForwardSearch, false);
68 
69  nh_private.param("feedback_frequency", ivFeedbackFrequency, 5.0);
70  nh_private.param("safe_execution", ivSafeExecution, true);
71 
72  nh_private.param("foot/max/step/x", ivMaxStepX, 0.07);
73  nh_private.param("foot/max/step/y", ivMaxStepY, 0.15);
74  nh_private.param("foot/max/step/theta", ivMaxStepTheta, 0.3);
75  nh_private.param("foot/max/inverse/step/x", ivMaxInvStepX, -0.03);
76  nh_private.param("foot/max/inverse/step/y", ivMaxInvStepY, 0.09);
77  nh_private.param("foot/max/inverse/step/theta", ivMaxInvStepTheta, -0.01);
78 
79  // step range
80  XmlRpc::XmlRpcValue step_range_x;
81  XmlRpc::XmlRpcValue step_range_y;
82  nh_private.getParam("step_range/x", step_range_x);
83  nh_private.getParam("step_range/y", step_range_y);
84  if (step_range_x.getType() != XmlRpc::XmlRpcValue::TypeArray)
85  ROS_ERROR("Error reading footsteps/x from config file.");
86  if (step_range_y.getType() != XmlRpc::XmlRpcValue::TypeArray)
87  ROS_ERROR("Error reading footsteps/y from config file.");
88  if (step_range_x.size() != step_range_y.size())
89  {
90  ROS_ERROR("Step range points have different size. Exit!");
91  exit(2);
92  }
93  // create step range
94  ivStepRange.clear();
95  ivStepRange.reserve(step_range_x.size());
96  double x, y;
97  for (int i = 0; i < step_range_x.size(); ++i)
98  {
99  x = (double)step_range_x[i];
100  y = (double)step_range_y[i];
101  ivStepRange.push_back(std::pair<double, double>(x, y));
102  }
103  // insert first point again at the end!
104  ivStepRange.push_back(ivStepRange[0]);
105 }
106 
107 
109 {}
110 
111 
112 bool
114 {
115  if (!updateStart())
116  {
117  ROS_ERROR("Start pose not accessible!");
118  return false;
119  }
120 
121  if (ivPlanner.plan())
122  {
123  startExecution();
124  return true;
125  }
126  // path planning unsuccessful
127  return false;
128 }
129 
130 
131 bool
133 {
134  if (!updateStart())
135  {
136  ROS_ERROR("Start pose not accessible!");
137  return false;
138  }
139 
140  bool path_existed = ivPlanner.pathExists();
141 
142  // calculate path by replanning (if no planning information exists
143  // this call is equal to ivPlanner.plan())
144  if (ivPlanner.replan())
145  {
146  startExecution();
147  return true;
148  }
149  else if (path_existed)
150  {
151  ROS_INFO("Replanning unsuccessful. Reseting previous planning "
152  "information.");
153  if (ivPlanner.plan())
154  {
155  startExecution();
156  return true;
157  }
158  }
159  // path planning unsuccessful
160  ivExecutingFootsteps = false;
161  return false;
162 }
163 
164 
165 void
167 {
168  if (ivSafeExecution)
169  {
171  new boost::thread(
172  boost::bind(&FootstepNavigation::executeFootsteps, this)));
173  }
174  else
175  {
176  // ALTERNATIVE:
178  }
179 }
180 
181 
182 void
184 {
185  if (ivPlanner.getPathSize() <= 1)
186  return;
187 
188  // lock this thread
189  ivExecutingFootsteps = true;
190 
191  ROS_INFO("Start walking towards the goal.");
192 
193  humanoid_nav_msgs::StepTarget step;
194  humanoid_nav_msgs::StepTargetService step_srv;
195 
196  tf::Transform from;
197  std::string support_foot_id;
198 
199  // calculate and perform relative footsteps until goal is reached
200  state_iter_t to_planned = ivPlanner.getPathBegin();
201  if (to_planned == ivPlanner.getPathEnd())
202  {
203  ROS_ERROR("No plan available. Return.");
204  return;
205  }
206 
207  const State* from_planned = to_planned.base();
208  to_planned++;
209  while (to_planned != ivPlanner.getPathEnd())
210  {
211  try
212  {
213  boost::this_thread::interruption_point();
214  }
215  catch (const boost::thread_interrupted&)
216  {
217  // leave this thread
218  return;
219  }
220 
221  if (from_planned->getLeg() == RIGHT)
222  support_foot_id = ivIdFootRight;
223  else // support_foot = LLEG
224  support_foot_id = ivIdFootLeft;
225 
226  // try to get real placement of the support foot
227  if (getFootTransform(support_foot_id, ivIdMapFrame, ros::Time::now(),
228  ros::Duration(0.5), &from))
229  {
230  // calculate relative step and check if it can be performed
231  if (getFootstep(from, *from_planned, *to_planned, &step))
232  {
233  step_srv.request.step = step;
234  ivFootstepSrv.call(step_srv);
235  }
236  // ..if it cannot be performed initialize replanning
237  else
238  {
239  ROS_INFO("Footstep cannot be performed. Replanning necessary.");
240 
241  replan();
242  // leave the thread
243  return;
244  }
245  }
246  else
247  {
248  // if the support foot could not be received wait and try again
249  ros::Duration(0.5).sleep();
250  continue;
251  }
252 
253  from_planned = to_planned.base();
254  to_planned++;
255  }
256  ROS_INFO("Succeeded walking to the goal.\n");
257 
258  // free the lock
259  ivExecutingFootsteps = false;
260 }
261 
262 
263 void
265 {
266  if (ivPlanner.getPathSize() <= 1)
267  return;
268 
269  // lock the planning and execution process
270  ivExecutingFootsteps = true;
271 
272  // make sure the action client is connected to the action server
274 
275  humanoid_nav_msgs::ExecFootstepsGoal goal;
276  State support_leg;
277  if (ivPlanner.getPathBegin()->getLeg() == RIGHT)
278  support_leg = ivPlanner.getStartFootRight();
279  else // leg == LEFT
280  support_leg = ivPlanner.getStartFootLeft();
281  if (getFootstepsFromPath(support_leg, 1, goal.footsteps))
282  {
283  goal.feedback_frequency = ivFeedbackFrequency;
284  ivControlStepIdx = 0;
285  ivResetStepIdx = 0;
286 
287  // start the execution via action; _1, _2 are place holders for
288  // function arguments (see boost doc)
290  goal,
291  boost::bind(&FootstepNavigation::doneCallback, this, _1, _2),
292  boost::bind(&FootstepNavigation::activeCallback, this),
293  boost::bind(&FootstepNavigation::feedbackCallback, this, _1));
294  }
295  else
296  {
297  // free the lock
298  ivExecutingFootsteps = false;
299 
300  replan();
301  }
302 }
303 
304 
305 void
307 {
308  // lock the execution
309  ivExecutingFootsteps = true;
310 
311  ROS_INFO("Start walking towards the goal.");
312 }
313 
314 
315 void
318  const humanoid_nav_msgs::ExecFootstepsResultConstPtr& result)
319 {
321  ROS_INFO("Succeeded walking to the goal.");
323  ROS_INFO("Preempted walking to the goal.");
324  // TODO: distinct between further states??
325  else
326  ROS_INFO("Failed walking to the goal.");
327 
328  // free the lock
329  ivExecutingFootsteps = false;
330 }
331 
332 
333 void
335  const humanoid_nav_msgs::ExecFootstepsFeedbackConstPtr& fb)
336 {
337  int executed_steps_idx = fb->executed_footsteps.size() - ivExecutionShift;
338  // make sure at least one step has been performed
339  if (executed_steps_idx < 0)
340  return;
341  // if the currently executed footstep equals the currently observed one
342  // everything is ok
343  if (executed_steps_idx == ivControlStepIdx)
344  return;
345 
346  // get planned foot placement
347  const State& planned = *(ivPlanner.getPathBegin() + ivControlStepIdx + 1 +
349  // get executed foot placement
350  tf::Transform executed_tf;
351  std::string foot_id;
352  if (planned.getLeg() == RIGHT)
353  foot_id = ivIdFootRight;
354  else
355  foot_id = ivIdFootLeft;
356 
358  ros::Duration(0.5), &executed_tf))
359  {
360  State executed(executed_tf.getOrigin().x(), executed_tf.getOrigin().y(),
361  tf::getYaw(executed_tf.getRotation()), planned.getLeg());
363  humanoid_nav_msgs::ExecFootstepsGoal goal;
364  // try to reach the calculated path
365  if (getFootstepsFromPath(executed, executed_steps_idx + ivResetStepIdx,
366  goal.footsteps))
367  {
368  goal.feedback_frequency = ivFeedbackFrequency;
369  // adjust the internal counters
371  ivControlStepIdx = 0;
372 
373  // restart the footstep execution
375  goal,
376  boost::bind(&FootstepNavigation::doneCallback, this, _1, _2),
377  boost::bind(&FootstepNavigation::activeCallback, this),
378  boost::bind(&FootstepNavigation::feedbackCallback, this, _1));
379  }
380  // the previously calculated path cannot be reached so we have plan
381  // a new path
382  else
383  {
384  replan();
385  }
386  }
387 
388  State executed(executed_tf.getOrigin().x(), executed_tf.getOrigin().y(),
389  tf::getYaw(executed_tf.getRotation()), planned.getLeg());
390 
391  // check if the currently executed footstep is no longer observed (i.e.
392  // the robot no longer follows its calculated path)
393  if (executed_steps_idx >= ivControlStepIdx + 2)
394  {
396 
397  ROS_DEBUG("Footstep execution incorrect.");
398 
399  humanoid_nav_msgs::ExecFootstepsGoal goal;
400  // try to reach the calculated path
401  if (getFootstepsFromPath(executed, executed_steps_idx + ivResetStepIdx,
402  goal.footsteps))
403  {
404  ROS_INFO("Try to reach calculated path.");
405 
406  goal.feedback_frequency = ivFeedbackFrequency;
407  // adjust the internal counters
409  ivControlStepIdx = 0;
410 
411  // restart the footstep execution
413  goal,
414  boost::bind(&FootstepNavigation::doneCallback, this, _1, _2),
415  boost::bind(&FootstepNavigation::activeCallback, this),
416  boost::bind(&FootstepNavigation::feedbackCallback, this, _1));
417  }
418  // the previously calculated path cannot be reached so we have plan
419  // a new path
420  else
421  {
422  replan();
423  }
424 
425  return;
426  }
427  // check the currently observed footstep
428  else
429  {
430  ROS_DEBUG("planned (%f, %f, %f, %i) vs. executed (%f, %f, %f, %i)",
431  planned.getX(), planned.getY(), planned.getTheta(),
432  planned.getLeg(),
433  executed.getX(), executed.getY(), executed.getTheta(),
434  executed.getLeg());
435 
436  // adjust the internal step counters if the footstep has been
437  // performed correctly; otherwise check in the next iteration if
438  // the step really has been incorrect
439  if (performanceValid(planned, executed))
441  else
442  ROS_DEBUG("Invalid step. Wait next step update before declaring"
443  " step incorrect.");
444  }
445 }
446 
447 
448 void
450  const geometry_msgs::PoseStampedConstPtr& goal_pose)
451 {
452  // check if the execution is locked
454  {
455  ROS_INFO("Already performing a navigation task. Wait until it is "
456  "finished.");
457  return;
458  }
459 
460  if (setGoal(goal_pose))
461  {
462  // this check enforces a planning from scratch if necessary (dependent on
463  // planning direction)
464  if (ivForwardSearch)
465  replan();
466  else
467  plan();
468  }
469 }
470 
471 
472 void
474  const nav_msgs::OccupancyGridConstPtr& occupancy_map)
475 {
476  // stop execution if an execution was performed
478  {
479  if (ivSafeExecution)
480  {
481  // interrupt the thread and wait until it has finished its execution
482  ivFootstepExecutionPtr->interrupt();
483  ivFootstepExecutionPtr->join();
484  }
485  else
486  {
488  }
489  }
490 
491  gridmap_2d::GridMap2DPtr map(new gridmap_2d::GridMap2D(occupancy_map));
492  ivIdMapFrame = map->getFrameID();
493 
494  // updates the map and starts replanning if necessary
495  if (ivPlanner.updateMap(map))
496  {
497  replan();
498  }
499 }
500 
501 
502 bool
503 FootstepNavigation::setGoal(const geometry_msgs::PoseStampedConstPtr goal_pose)
504 {
505  return setGoal(goal_pose->pose.position.x,
506  goal_pose->pose.position.y,
507  tf::getYaw(goal_pose->pose.orientation));
508 }
509 
510 
511 bool
512 FootstepNavigation::setGoal(float x, float y, float theta)
513 {
514  return ivPlanner.setGoal(x, y, theta);
515 }
516 
517 
518 bool
520 {
521  ros::Duration(0.5).sleep();
522 
523  tf::Transform foot_left, foot_right;
524  {
525  // get real placement of the feet
527  ros::Duration(0.5), &foot_left))
528  {
529  if (ivPlanner.pathExists())
530  {
531  ivExecutingFootsteps = false;
532  }
533  return false;
534  }
536  ros::Duration(0.5), &foot_right))
537  {
538  if (ivPlanner.pathExists())
539  {
540  ivExecutingFootsteps = false;
541  }
542  return false;
543  }
544  }
545  State left(foot_left.getOrigin().x(), foot_left.getOrigin().y(),
546  tf::getYaw(foot_left.getRotation()), LEFT);
547  State right(foot_right.getOrigin().x(), foot_right.getOrigin().y(),
548  tf::getYaw(foot_right.getRotation()), RIGHT);
549 
550  ROS_INFO("Robot standing at (%f, %f, %f, %i) (%f, %f, %f, %i).",
551  left.getX(), left.getY(), left.getTheta(), left.getLeg(),
552  right.getX(), right.getY(), right.getTheta(), right.getLeg());
553 
554  return ivPlanner.setStart(left, right);
555 }
556 
557 
558 bool
560  const State& from_planned,
561  const State& to,
562  humanoid_nav_msgs::StepTarget* footstep)
563 {
564  // get footstep to reach 'to' from 'from'
565  tf::Transform step = from.inverse() *
567  tf::Point(to.getX(), to.getY(), 0.0));
568 
569  // set the footstep
570  footstep->pose.x = step.getOrigin().x();
571  footstep->pose.y = step.getOrigin().y();
572  footstep->pose.theta = tf::getYaw(step.getRotation());
573  if (to.getLeg() == LEFT)
574  footstep->leg = humanoid_nav_msgs::StepTarget::left;
575  else // to.leg == RIGHT
576  footstep->leg = humanoid_nav_msgs::StepTarget::right;
577 
578 
579  /* check if the footstep can be performed by the NAO robot ******************/
580 
581  // check if the step lies within the executable range
582  if (performable(*footstep))
583  {
584  return true;
585  }
586  else
587  {
588  // check if there is only a minor divergence between the current support
589  // foot and the foot placement used during the plannig task: in such a case
590  // perform the step that has been used during the planning
591  float step_diff_x = fabs(from.getOrigin().x() - from_planned.getX());
592  float step_diff_y = fabs(from.getOrigin().y() - from_planned.getY());
593  float step_diff_theta = fabs(
595  tf::getYaw(from.getRotation()), from_planned.getTheta()));
596  if (step_diff_x < ivAccuracyX && step_diff_y < ivAccuracyY &&
597  step_diff_theta < ivAccuracyTheta)
598  {
599  step = tf::Pose(tf::createQuaternionFromYaw(from_planned.getTheta()),
600  tf::Point(from_planned.getX(), from_planned.getY(), 0.0)
601  ).inverse() *
603  tf::Point(to.getX(), to.getY(), 0.0));
604 
605  footstep->pose.x = step.getOrigin().x();
606  footstep->pose.y = step.getOrigin().y();
607  footstep->pose.theta = tf::getYaw(step.getRotation());
608 
609  return true;
610  }
611 
612  return false;
613  }
614 
615 // // ALTERNATIVE: clip the footstep into the executable range; if nothing was
616 // // clipped: perform; if too much was clipped: do not perform
617 // humanoid_nav_msgs::ClipFootstep footstep_clip;
618 // footstep_clip.request.step = footstep;
619 // ivClipFootstepSrv.call(footstep_clip);
620 //
621 // if (performanceValid(footstep_clip))
622 // {
623 // footstep.pose.x = footstep_clip.response.step.pose.x;
624 // footstep.pose.y = footstep_clip.response.step.pose.y;
625 // footstep.pose.theta = footstep_clip.response.step.pose.theta;
626 // return true;
627 // }
628 // else
629 // {
630 // return false;
631 // }
632 }
633 
634 
635 bool
637  const State& current_support_leg, int starting_step_num,
638  std::vector<humanoid_nav_msgs::StepTarget>& footsteps)
639 {
640  humanoid_nav_msgs::StepTarget footstep;
641 
642  state_iter_t to_planned = ivPlanner.getPathBegin() + starting_step_num - 1;
643  tf::Pose last(tf::createQuaternionFromYaw(current_support_leg.getTheta()),
644  tf::Point(current_support_leg.getX(), current_support_leg.getY(),
645  0.0));
646  const State* from_planned = to_planned.base();
647  to_planned++;
648  for (; to_planned != ivPlanner.getPathEnd(); to_planned++)
649  {
650  if (getFootstep(last, *from_planned, *to_planned, &footstep))
651  {
652  footsteps.push_back(footstep);
653  }
654  else
655  {
656  ROS_ERROR("Calculated path cannot be performed!");
657  return false;
658  }
659 
660  last = tf::Pose(tf::createQuaternionFromYaw(to_planned->getTheta()),
661  tf::Point(to_planned->getX(), to_planned->getY(), 0.0));
662  from_planned = to_planned.base();
663  }
664 
665  return true;
666 }
667 
668 
669 bool
670 FootstepNavigation::getFootTransform(const std::string& foot_id,
671  const std::string& world_frame_id,
672  const ros::Time& time,
673  const ros::Duration& waiting_time,
674  tf::Transform* foot)
675 {
676  tf::StampedTransform stamped_foot_transform;
677  try
678  {
679  ivTransformListener.waitForTransform(world_frame_id, foot_id, time,
680  waiting_time);
681  ivTransformListener.lookupTransform(world_frame_id, foot_id, time,
682  stamped_foot_transform);
683  }
684  catch (const tf::TransformException& e)
685  {
686  ROS_WARN("Failed to obtain FootTransform from tf (%s)", e.what());
687  return false;
688  }
689 
690  foot->setOrigin(stamped_foot_transform.getOrigin());
691  foot->setRotation(stamped_foot_transform.getRotation());
692 
693  return true;
694 }
695 
696 
697 bool
698 FootstepNavigation::performanceValid(float a_x, float a_y, float a_theta,
699  float b_x, float b_y, float b_theta)
700 {
701  return (fabs(a_x - b_x) < ivAccuracyX &&
702  fabs(a_y - b_y) < ivAccuracyY &&
703  fabs(angles::shortest_angular_distance(a_theta, b_theta)) <
705 }
706 
707 
708 bool
710  const humanoid_nav_msgs::ClipFootstep& step)
711 {
712  return performanceValid(step.request.step.pose.x,
713  step.request.step.pose.y,
714  step.request.step.pose.theta,
715  step.response.step.pose.x,
716  step.response.step.pose.y,
717  step.response.step.pose.theta);
718 }
719 
720 
721 bool
723  const State& executed)
724 {
725  return performanceValid(
726  planned.getX(), planned.getY(), planned.getTheta(),
727  executed.getX(), executed.getY(), executed.getTheta());
728 }
729 
730 
731 bool
732 FootstepNavigation::performable(const humanoid_nav_msgs::StepTarget& footstep)
733 {
734  float step_x = footstep.pose.x;
735  float step_y = footstep.pose.y;
736  float step_theta = footstep.pose.theta;
737 
738  if (footstep.leg == humanoid_nav_msgs::StepTarget::right)
739  {
740  step_y = -step_y;
741  step_theta = -step_theta;
742  }
743 
744  if (step_x + FLOAT_CMP_THR > ivMaxStepX ||
745  step_x - FLOAT_CMP_THR < ivMaxInvStepX)
746  return false;
747  if (step_y + FLOAT_CMP_THR > ivMaxStepY ||
748  step_y - FLOAT_CMP_THR < ivMaxInvStepY)
749  return false;
750  if (step_theta + FLOAT_CMP_THR > ivMaxStepTheta ||
751  step_theta - FLOAT_CMP_THR < ivMaxInvStepTheta)
752  return false;
753 
754  return performable(step_x, step_y);
755 }
756 
757 
758 bool
759 FootstepNavigation::performable(float step_x, float step_y)
760 {
761  int cn = 0;
762 
763  // loop through all ivStepRange of the polygon
764  for(unsigned int i = 0; i < ivStepRange.size() - 1; ++i)
765  {
766  if ((ivStepRange[i].second <= step_y &&
767  ivStepRange[i + 1].second > step_y) ||
768  (ivStepRange[i].second >= step_y &&
769  ivStepRange[i + 1].second < step_y))
770  {
771  float vt = (float)(step_y - ivStepRange[i].second) /
772  (ivStepRange[i + 1].second - ivStepRange[i].second);
773  if (step_x <
774  ivStepRange[i].first + vt *
775  (ivStepRange[i + 1].first - ivStepRange[i].first))
776  {
777  ++cn;
778  }
779  }
780  }
781  return cn & 1;
782 }
783 }
void executeFootstepsFast()
Alternative (and more fluid) execution of footsteps using ROS&#39; actionlib.
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
double getTheta() const
Definition: State.h:48
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool setGoal(const State &left_foot, const State &right_foot)
Sets the goal pose as two feet (left / right)
bool replan()
Starts the planning task. First FootstepPlanner::replan() is called to use planning information from ...
bool plan(bool force_new_plan=true)
Start a planning task from scratch (will delete information of previous planning tasks). Map and start, goal poses need to be set beforehand.
bool setGoal(const geometry_msgs::PoseStampedConstPtr goal_pose)
Wrapper for FootstepPlanner::setGoal.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool getFootstepsFromPath(const State &current_support_leg, int starting_step_num, std::vector< humanoid_nav_msgs::StepTarget > &footsteps)
Extracts the footsteps necessary to perform the calculated path.
int size() const
static double getYaw(const Quaternion &bt_q)
bool sleep() const
bool call(MReq &req, MRes &res)
static const double FLOAT_CMP_THR
Definition: helper.h:39
void activeCallback()
Called from within ROS&#39; actionlib at the start of a new goal request.
Type const & getType() const
bool updateMap(const gridmap_2d::GridMap2DPtr map)
Updates the map in the planning environment.
#define ROS_WARN(...)
state_iter_t getPathEnd() const
const int ivExecutionShift
Fixed delay (=2) of the incoming footsteps.
actionlib::SimpleActionClient< humanoid_nav_msgs::ExecFootstepsAction > ivFootstepsExecution
Simple action client to control a footstep execution.
bool updateStart()
Updates the robot&#39;s current pose.
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
double getX() const
Definition: State.h:46
TFSIMD_FORCE_INLINE const tfScalar & x() const
tf::Transform Pose
bool replan()
Starts a planning task based on previous planning information (note that this method can also be used...
A class representing the robot&#39;s pose (i.e. position and orientation) in the (continuous) world view...
Definition: State.h:34
bool getFootstep(const tf::Pose &from, const State &from_planned, const State &to, humanoid_nav_msgs::StepTarget *footstep)
Calculates the footstep necessary to reach &#39;to&#39; from within &#39;from&#39;.
static Quaternion createQuaternionFromYaw(double yaw)
bool performable(const humanoid_nav_msgs::StepTarget &footstep)
state_iter_t getPathBegin() const
#define ROS_INFO(...)
void goalPoseCallback(const geometry_msgs::PoseStampedConstPtr &goal_pose)
Callback to set a simulated robot at a certain pose.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double getY() const
Definition: State.h:47
bool performanceValid(const humanoid_nav_msgs::ClipFootstep &footstep)
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::pair< double, double > > ivStepRange
bool ivExecutingFootsteps
Used to lock the calculation and execution of footsteps.
void doneCallback(const actionlib::SimpleClientGoalState &state, const humanoid_nav_msgs::ExecFootstepsResultConstPtr &result)
Called from within ROS&#39; actionlib at the end of a goal request.
double ivFeedbackFrequency
The rate the action server sends its feedback.
Transform inverse() const
void startExecution()
Starts the execution of the calculated path.
bool plan()
Starts the planning task from scratch discarding previous planning information.
bool getFootTransform(const std::string &foot_id, const std::string &world_frame_id, const ros::Time &time, const ros::Duration &waiting_time, tf::Transform *foot)
Obtains the pose of the robot&#39;s foot from tf.
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
unsigned int step
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancy_map)
Callback to set the map.
Quaternion getRotation() const
bool getParam(const std::string &key, std::string &s) const
static Time now()
std::vector< State >::const_iterator state_iter_t
void feedbackCallback(const humanoid_nav_msgs::ExecFootstepsFeedbackConstPtr &fb)
Called from within ROS&#39; actionlib during the execution of a goal request.
Leg getLeg() const
Definition: State.h:49
void executeFootsteps()
Executes footsteps as boost::thread.
boost::shared_ptr< boost::thread > ivFootstepExecutionPtr
#define ROS_ERROR(...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
def shortest_angular_distance(from_angle, to_angle)
bool ivSafeExecution
Whether to use the slower but more cautious execution or not.
bool setStart(const geometry_msgs::PoseStampedConstPtr start_pose)
Sets the start pose as a robot pose centered between two feet.
#define ROS_DEBUG(...)


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24