FootstepPlanner.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 #include <humanoid_nav_msgs/ClipFootstep.h>
23 
24 
27 
28 
29 namespace footstep_planner
30 {
32 : ivStartPoseSetUp(false),
33  ivGoalPoseSetUp(false),
34  ivLastMarkerMsgSize(0),
35  ivPathCost(0),
36  ivMarkerNamespace("")
37 {
38  // private NodeHandle for parameters and private messages (debug / info)
39  ros::NodeHandle nh_private("~");
40  ros::NodeHandle nh_public;
41 
42  // ..publishers
43  ivExpandedStatesVisPub = nh_private.advertise<
44  sensor_msgs::PointCloud>("expanded_states", 1);
45  ivRandomStatesVisPub = nh_private.advertise<
46  sensor_msgs::PointCloud>("random_states", 1);
47  ivFootstepPathVisPub = nh_private.advertise<
48  visualization_msgs::MarkerArray>("footsteps_array", 1);
49  ivHeuristicPathVisPub = nh_private.advertise<
50  nav_msgs::Path>("heuristic_path", 1);
51  ivPathVisPub = nh_private.advertise<nav_msgs::Path>("path", 1);
52  ivStartPoseVisPub = nh_private.advertise<
53  geometry_msgs::PoseStamped>("start", 1);
54 
55  std::string heuristic_type;
56  double diff_angle_cost;
57 
58  // read parameters from config file:
59  // planner environment settings
60  nh_private.param("heuristic_type", heuristic_type,
61  std::string("EuclideanHeuristic"));
62  nh_private.param("heuristic_scale", ivEnvironmentParams.heuristic_scale, 1.0);
63  nh_private.param("max_hash_size", ivEnvironmentParams.hash_table_size, 65536);
64  nh_private.param("accuracy/collision_check",
66  2);
67  nh_private.param("accuracy/cell_size", ivEnvironmentParams.cell_size, 0.01);
68  nh_private.param("accuracy/num_angle_bins",
70  64);
71  nh_private.param("step_cost", ivEnvironmentParams.step_cost, 0.05);
72  nh_private.param("diff_angle_cost", diff_angle_cost, 0.0);
73 
74  nh_private.param("planner_type", ivPlannerType, std::string("ARAPlanner"));
75  nh_private.param("search_until_first_solution", ivSearchUntilFirstSolution,
76  false);
77  nh_private.param("allocated_time", ivMaxSearchTime, 7.0);
78  nh_private.param("forward_search", ivEnvironmentParams.forward_search, false);
79  nh_private.param("initial_epsilon", ivInitialEpsilon, 3.0);
80  nh_private.param("changed_cells_limit", ivChangedCellsLimit, 20000);
81  nh_private.param("num_random_nodes", ivEnvironmentParams.num_random_nodes,
82  20);
83  nh_private.param("random_node_dist", ivEnvironmentParams.random_node_distance,
84  1.0);
85 
86  // footstep settings
87  nh_private.param("foot/size/x", ivEnvironmentParams.footsize_x, 0.16);
88  nh_private.param("foot/size/y", ivEnvironmentParams.footsize_y, 0.06);
89  nh_private.param("foot/size/z", ivEnvironmentParams.footsize_z, 0.015);
90  nh_private.param("foot/separation", ivFootSeparation, 0.1);
91  nh_private.param("foot/origin_shift/x",
93  0.02);
94  nh_private.param("foot/origin_shift/y",
96  0.0);
97  nh_private.param("foot/max/step/x", ivEnvironmentParams.max_footstep_x, 0.08);
98  nh_private.param("foot/max/step/y", ivEnvironmentParams.max_footstep_y, 0.16);
99  nh_private.param("foot/max/step/theta",
101  0.3);
102  nh_private.param("foot/max/inverse/step/x",
104  -0.04);
105  nh_private.param("foot/max/inverse/step/y",
107  0.09);
108  nh_private.param("foot/max/inverse/step/theta",
110  -0.3);
111 
112  // footstep discretization
113  XmlRpc::XmlRpcValue footsteps_x;
114  XmlRpc::XmlRpcValue footsteps_y;
115  XmlRpc::XmlRpcValue footsteps_theta;
116  nh_private.getParam("footsteps/x", footsteps_x);
117  nh_private.getParam("footsteps/y", footsteps_y);
118  nh_private.getParam("footsteps/theta", footsteps_theta);
119  if (footsteps_x.getType() != XmlRpc::XmlRpcValue::TypeArray)
120  ROS_ERROR("Error reading footsteps/x from config file.");
121  if (footsteps_y.getType() != XmlRpc::XmlRpcValue::TypeArray)
122  ROS_ERROR("Error reading footsteps/y from config file.");
123  if (footsteps_theta.getType() != XmlRpc::XmlRpcValue::TypeArray)
124  ROS_ERROR("Error reading footsteps/theta from config file.");
125  int size_x = footsteps_x.size();
126  int size_y = footsteps_y.size();
127  int size_t = footsteps_theta.size();
128  if (size_x != size_y || size_x != size_t)
129  {
130  ROS_ERROR("Footstep parameterization has different sizes for x/y/theta. "
131  "Exit!");
132  exit(2);
133  }
134  // create footstep set
136  double max_step_width = 0;
137  for(int i=0; i < footsteps_x.size(); ++i)
138  {
139  double x = (double)footsteps_x[i];
140  double y = (double)footsteps_y[i];
141  double theta = (double)footsteps_theta[i];
142 
143  Footstep f(x, y, theta,
147  ivEnvironmentParams.footstep_set.push_back(f);
148 
149  double cur_step_width = sqrt(x*x + y*y);
150 
151  if (cur_step_width > max_step_width)
152  max_step_width = cur_step_width;
153  }
154 
155  // step range
156  XmlRpc::XmlRpcValue step_range_x;
157  XmlRpc::XmlRpcValue step_range_y;
158  nh_private.getParam("step_range/x", step_range_x);
159  nh_private.getParam("step_range/y", step_range_y);
160  if (step_range_x.getType() != XmlRpc::XmlRpcValue::TypeArray)
161  ROS_ERROR("Error reading footsteps/x from config file.");
162  if (step_range_y.getType() != XmlRpc::XmlRpcValue::TypeArray)
163  ROS_ERROR("Error reading footsteps/y from config file.");
164  if (step_range_x.size() != step_range_y.size())
165  {
166  ROS_ERROR("Step range points have different size. Exit!");
167  exit(2);
168  }
169  // create step range
171  ivEnvironmentParams.step_range.reserve(step_range_x.size());
172  double x, y;
173  double max_x = 0.0;
174  double max_y = 0.0;
175  double cell_size = ivEnvironmentParams.cell_size;
176  for (int i=0; i < step_range_x.size(); ++i)
177  {
178  x = (double)step_range_x[i];
179  y = (double)step_range_y[i];
180  if (fabs(x) > max_x)
181  max_x = fabs(x);
182  if (fabs(y) > max_y)
183  max_y = fabs(y);
185  std::pair<int, int>(disc_val(x, cell_size), disc_val(y, cell_size)));
186  }
187  // insert first point again at the end!
189  ivEnvironmentParams.max_step_width = sqrt(max_x*max_x + max_y*max_y) * 1.5;
190 
191  // initialize the heuristic
193  if (heuristic_type == "EuclideanHeuristic")
194  {
195  h.reset(
198  ROS_INFO("FootstepPlanner heuristic: euclidean distance");
199  }
200  else if(heuristic_type == "EuclStepCostHeuristic")
201  {
202  h.reset(
206  diff_angle_cost,
207  max_step_width));
208  ROS_INFO("FootstepPlanner heuristic: euclidean distance with step costs");
209  }
210  else if (heuristic_type == "PathCostHeuristic")
211  {
212  // for heuristic inflation
213  double foot_incircle =
214  std::min((ivEnvironmentParams.footsize_x / 2.0 -
218  assert(foot_incircle > 0.0);
219 
220  h.reset(
224  diff_angle_cost,
225  max_step_width,
226  foot_incircle));
227  ROS_INFO("FootstepPlanner heuristic: 2D path euclidean distance with step "
228  "costs");
229 
230  // keep a local ptr for visualization
231  ivPathCostHeuristicPtr = boost::dynamic_pointer_cast<PathCostHeuristic>(h);
232  }
233  else
234  {
235  ROS_ERROR_STREAM("Heuristic " << heuristic_type << " not available, "
236  "exiting.");
237  exit(1);
238  }
240 
241  // initialize the planner environment
244 
245  // set up planner
246  if (ivPlannerType == "ARAPlanner" ||
247  ivPlannerType == "ADPlanner" ||
248  ivPlannerType == "RSTARPlanner" )
249  {
250  ROS_INFO_STREAM("Planning with " << ivPlannerType);
251  }
252  else
253  {
254  ROS_ERROR_STREAM("Planner "<< ivPlannerType <<" not available / "
255  "untested.");
256  exit(1);
257  }
259  {
260  ROS_INFO_STREAM("Search direction: forward planning");
261  }
262  else
263  {
264  ROS_INFO_STREAM("Search direction: backward planning");
265  }
266  setPlanner();
267 }
268 
269 
271 {}
272 
273 
274 void
276 {
277  if (ivPlannerType == "ARAPlanner")
278  {
279  ivPlannerPtr.reset(
280  new ARAPlanner(ivPlannerEnvironmentPtr.get(),
282  }
283  else if (ivPlannerType == "ADPlanner")
284  {
285  ivPlannerPtr.reset(
286  new ADPlanner(ivPlannerEnvironmentPtr.get(),
288  }
289  else if (ivPlannerType == "RSTARPlanner")
290  {
291  RSTARPlanner* p =
292  new RSTARPlanner(ivPlannerEnvironmentPtr.get(),
294  // new options, require patched SBPL
295  // p->set_local_expand_thres(500);
296  // p->set_eps_step(1.0);
297  ivPlannerPtr.reset(p);
298  }
299  // else if (ivPlannerType == "ANAPlanner")
300  // ivPlannerPtr.reset(new anaPlanner(ivPlannerEnvironmentPtr.get(),
301  // ivForwardSearch));
302 }
303 
304 
305 bool
307 {
308  bool path_existed = (bool)ivPath.size();
309  int ret = 0;
310  MDPConfig mdp_config;
311  std::vector<int> solution_state_ids;
312 
313  // commit start/goal poses to the environment
316  ivPlannerEnvironmentPtr->updateHeuristicValues();
317  ivPlannerEnvironmentPtr->InitializeEnv(NULL);
318  ivPlannerEnvironmentPtr->InitializeMDPCfg(&mdp_config);
319 
320  // inform AD planner about changed (start) states for replanning
321  if (path_existed &&
323  ivPlannerType == "ADPlanner")
324  {
325  std::vector<int> changed_edges;
326  changed_edges.push_back(mdp_config.startstateid);
327  // update the AD planner
328  boost::shared_ptr<ADPlanner> ad_planner =
329  boost::dynamic_pointer_cast<ADPlanner>(ivPlannerPtr);
330  ad_planner->update_preds_of_changededges(&changed_edges);
331  }
332 
333  // set up SBPL
334  if (ivPlannerPtr->set_start(mdp_config.startstateid) == 0)
335  {
336  ROS_ERROR("Failed to set start state.");
337  return false;
338  }
339  if (ivPlannerPtr->set_goal(mdp_config.goalstateid) == 0)
340  {
341  ROS_ERROR("Failed to set goal state\n");
342  return false;
343  }
344 
345  ivPlannerPtr->set_initialsolution_eps(ivInitialEpsilon);
346  ivPlannerPtr->set_search_mode(ivSearchUntilFirstSolution);
347 
348  ROS_INFO("Start planning (max time: %f, initial eps: %f (%f))\n",
350  ivPlannerPtr->get_initial_eps());
351  int path_cost;
352  ros::WallTime startTime = ros::WallTime::now();
353  try
354  {
355  ret = ivPlannerPtr->replan(ivMaxSearchTime, &solution_state_ids,
356  &path_cost);
357  }
358  catch (const SBPL_Exception& e)
359  {
360  // ROS_ERROR("SBPL planning failed (%s)", e.what());
361  return false;
362  }
364 
365  bool path_is_new = pathIsNew(solution_state_ids);
366  if (ret && solution_state_ids.size() > 0)
367  {
368  if (!path_is_new)
369  ROS_WARN("Solution found by SBPL is the same as the old solution. This could indicate that replanning failed.");
370 
371  ROS_INFO("Solution of size %zu found after %f s",
372  solution_state_ids.size(),
373  (ros::WallTime::now()-startTime).toSec());
374 
375  if (extractPath(solution_state_ids))
376  {
377  ROS_INFO("Expanded states: %i total / %i new",
378  ivPlannerEnvironmentPtr->getNumExpandedStates(),
379  ivPlannerPtr->get_n_expands());
380  ROS_INFO("Final eps: %f", ivPlannerPtr->get_final_epsilon());
381  ROS_INFO("Path cost: %f (%i)\n", ivPathCost, path_cost);
382 
383  ivPlanningStatesIds = solution_state_ids;
384 
389 
390  return true;
391  }
392  else
393  {
394  ROS_ERROR("extracting path failed\n\n");
395  return false;
396  }
397  }
398  else
399  {
402 
403  ROS_ERROR("No solution found");
404  return false;
405  }
406 }
407 
408 
409 bool
410 FootstepPlanner::extractPath(const std::vector<int>& state_ids)
411 {
412  ivPath.clear();
413 
414  State s;
416  std::vector<int>::const_iterator state_ids_iter = state_ids.begin();
417 
418  // first state is always the robot's left foot
419  if (!ivPlannerEnvironmentPtr->getState(*state_ids_iter, &start_left))
420  {
421  ivPath.clear();
422  return false;
423  }
424  ++state_ids_iter;
425  if (!ivPlannerEnvironmentPtr->getState(*state_ids_iter, &s))
426  {
427  ivPath.clear();
428  return false;
429  }
430  ++state_ids_iter;
431 
432  // check if the robot's left foot can be ommited as first state in the path,
433  // i.e. the robot's right foot is appended first to the path
434  if (s.getLeg() == LEFT)
435  ivPath.push_back(ivStartFootRight);
436  else
437  ivPath.push_back(start_left);
438  ivPath.push_back(s);
439 
440  for(; state_ids_iter < state_ids.end(); ++state_ids_iter)
441  {
442  if (!ivPlannerEnvironmentPtr->getState(*state_ids_iter, &s))
443  {
444  ivPath.clear();
445  return false;
446  }
447  ivPath.push_back(s);
448  }
449 
450  // add last neutral step
451  if (ivPath.back().getLeg() == RIGHT)
452  ivPath.push_back(ivGoalFootLeft);
453  else // last_leg == LEFT
454  ivPath.push_back(ivGoalFootRight);
455 
456  return true;
457 }
458 
459 
460 void
462 {
463  ROS_INFO("Resetting planner");
464  // reset the previously calculated paths
465  ivPath.clear();
466  ivPlanningStatesIds.clear();
467  // reset the planner
468  // INFO: force_planning_from_scratch was not working properly the last time
469  // checked; therefore instead of using this function the planner is manually
470  // reset
471  //ivPlannerPtr->force_planning_from_scratch();
472  ivPlannerEnvironmentPtr->reset();
473  setPlanner();
474 }
475 
476 
477 void
479 {
480  ROS_INFO("Resetting planner and environment");
481  // reset the previously calculated paths
482  ivPath.clear();
483  ivPlanningStatesIds.clear();
484  // reinitialize the planner environment
487  setPlanner();
488 }
489 
490 
491 bool
492 FootstepPlanner::plan(bool force_new_plan)
493 {
494  if (!ivMapPtr)
495  {
496  ROS_ERROR("FootstepPlanner has no map for planning yet.");
497  return false;
498  }
500  {
501  ROS_ERROR("FootstepPlanner has not set the start and/or goal pose "
502  "yet.");
503  return false;
504  }
505 
506  if (force_new_plan
507  || ivPlannerType == "RSTARPlanner" || ivPlannerType == "ARAPlanner" )
508  {
509  reset();
510  }
511  // start the planning and return success
512  return run();
513 }
514 
515 
516 bool
518 {
519  return plan(false);
520 }
521 
522 
523 bool
524 FootstepPlanner::plan(const geometry_msgs::PoseStampedConstPtr start,
525  const geometry_msgs::PoseStampedConstPtr goal)
526 {
527  return plan(start->pose.position.x, start->pose.position.y,
528  tf::getYaw(start->pose.orientation),
529  goal->pose.position.x, goal->pose.position.y,
530  tf::getYaw(goal->pose.orientation));
531 }
532 
533 
534 bool
535 FootstepPlanner::plan(float start_x, float start_y, float start_theta,
536  float goal_x, float goal_y, float goal_theta)
537 {
538  if (!(setStart(start_x, start_y, start_theta) &&
539  setGoal(goal_x, goal_y, goal_theta)))
540  {
541  return false;
542  }
543 
544  return plan(false);
545 }
546 
547 
548 bool
549 FootstepPlanner::planService(humanoid_nav_msgs::PlanFootsteps::Request &req,
550  humanoid_nav_msgs::PlanFootsteps::Response &resp)
551 {
552  bool result = plan(req.start.x, req.start.y, req.start.theta,
553  req.goal.x, req.goal.y, req.goal.theta);
554 
555  resp.costs = getPathCosts();
556  resp.footsteps.reserve(getPathSize());
557  resp.final_eps = ivPlannerPtr->get_final_epsilon();
558  resp.expanded_states = ivPlannerEnvironmentPtr->getNumExpandedStates();
559  extractFootstepsSrv(resp.footsteps);
560 
561  resp.result = result;
562 
563  // return true since service call was successful (independent from the
564  // success of the planning call)
565  return true;
566 }
567 
568 
569 bool
570 FootstepPlanner::planFeetService(humanoid_nav_msgs::PlanFootstepsBetweenFeet::Request &req,
571  humanoid_nav_msgs::PlanFootstepsBetweenFeet::Response &resp)
572 {
573  // TODO check direction and change of states, force planning from scratch if does not fit
574  setStart(State(req.start_left.pose.x, req.start_left.pose.y, req.start_left.pose.theta, LEFT),
575  State(req.start_right.pose.x, req.start_right.pose.y, req.start_right.pose.theta, RIGHT));
576  setGoal(State(req.goal_left.pose.x, req.goal_left.pose.y, req.goal_left.pose.theta, LEFT),
577  State(req.goal_right.pose.x, req.goal_right.pose.y, req.goal_right.pose.theta, RIGHT));
578 
579  bool result = plan(false);
580 
581  resp.costs = getPathCosts();
582  resp.footsteps.reserve(getPathSize());
583  resp.final_eps = ivPlannerPtr->get_final_epsilon();
584  resp.expanded_states = ivPlannerEnvironmentPtr->getNumExpandedStates();
585  extractFootstepsSrv(resp.footsteps);
586 
587  resp.result = result;
588 
589  // return true since service call was successful (independent from the
590  // success of the planning call)
591  return true;
592 }
593 
594 void
595 FootstepPlanner::extractFootstepsSrv(std::vector<humanoid_nav_msgs::StepTarget> & footsteps) const{
596  humanoid_nav_msgs::StepTarget foot;
597  state_iter_t path_iter;
598  for (path_iter = getPathBegin(); path_iter != getPathEnd(); ++path_iter)
599  {
600  foot.pose.x = path_iter->getX();
601  foot.pose.y = path_iter->getY();
602  foot.pose.theta = path_iter->getTheta();
603  if (path_iter->getLeg() == LEFT)
604  foot.leg = humanoid_nav_msgs::StepTarget::left;
605  else if (path_iter->getLeg() == RIGHT)
606  foot.leg = humanoid_nav_msgs::StepTarget::right;
607  else
608  {
609  ROS_ERROR("Footstep pose at (%f, %f, %f) is set to NOLEG!",
610  path_iter->getX(), path_iter->getY(),
611  path_iter->getTheta());
612  continue;
613  }
614 
615  footsteps.push_back(foot);
616  }
617 
618 }
619 
620 
621 void
623  const geometry_msgs::PoseStampedConstPtr& goal_pose)
624 {
625  // update the goal states in the environment
626  if (setGoal(goal_pose))
627  {
628  if (ivStartPoseSetUp)
629  {
630  // force planning from scratch when backwards direction
632  }
633  }
634 }
635 
636 
637 void
639  const geometry_msgs::PoseWithCovarianceStampedConstPtr& start_pose)
640 {
641  if (setStart(start_pose->pose.pose.position.x,
642  start_pose->pose.pose.position.y,
643  tf::getYaw(start_pose->pose.pose.orientation)))
644  {
645  if (ivGoalPoseSetUp)
646  {
647  // force planning from scratch when forward direction
649  }
650  }
651 }
652 
653 
654 void
656  const nav_msgs::OccupancyGridConstPtr& occupancy_map)
657 {
658  GridMap2DPtr map(new GridMap2D(occupancy_map));
659 
660  // new map: update the map information
661  if (updateMap(map))
662  {
663  // NOTE: update map currently simply resets the planner, i.e. replanning
664  // here is in fact a planning from the scratch
665  plan(false);
666  }
667 }
668 
669 
670 bool
671 FootstepPlanner::setGoal(const geometry_msgs::PoseStampedConstPtr goal_pose)
672 {
673  return setGoal(goal_pose->pose.position.x,
674  goal_pose->pose.position.y,
675  tf::getYaw(goal_pose->pose.orientation));
676 }
677 
678 
679 bool
680 FootstepPlanner::setGoal(float x, float y, float theta)
681 {
682  if (!ivMapPtr)
683  {
684  ROS_ERROR("Distance map hasn't been initialized yet.");
685  return false;
686  }
687 
688  State goal(x, y, theta, NOLEG);
689  State foot_left = getFootPose(goal, LEFT);
690  State foot_right = getFootPose(goal, RIGHT);
691 
692  if (ivPlannerEnvironmentPtr->occupied(foot_left) ||
693  ivPlannerEnvironmentPtr->occupied(foot_right))
694  {
695  ROS_ERROR("Goal pose at (%f %f %f) not accessible.", x, y, theta);
696  ivGoalPoseSetUp = false;
697  return false;
698  }
699  ivGoalFootLeft = foot_left;
700  ivGoalFootRight = foot_right;
701 
702  ivGoalPoseSetUp = true;
703  ROS_INFO("Goal pose set to (%f %f %f)", x, y, theta);
704 
705  return true;
706 }
707 
708 bool
709 FootstepPlanner::setGoal(const State& left_foot, const State& right_foot)
710 {
711  if (ivPlannerEnvironmentPtr->occupied(left_foot) ||
712  ivPlannerEnvironmentPtr->occupied(right_foot))
713  {
714  ivGoalPoseSetUp = false;
715  return false;
716  }
717  ivGoalFootLeft = left_foot;
718  ivGoalFootRight = right_foot;
719 
720  ivGoalPoseSetUp = true;
721 
722  return true;
723 }
724 
725 
726 bool
727 FootstepPlanner::setStart(const geometry_msgs::PoseStampedConstPtr start_pose)
728 {
729  return setStart(start_pose->pose.position.x,
730  start_pose->pose.position.y,
731  tf::getYaw(start_pose->pose.orientation));
732 }
733 
734 
735 bool
736 FootstepPlanner::setStart(const State& left_foot, const State& right_foot)
737 {
738  if (ivPlannerEnvironmentPtr->occupied(left_foot) ||
739  ivPlannerEnvironmentPtr->occupied(right_foot))
740  {
741  ivStartPoseSetUp = false;
742  return false;
743  }
744  ivStartFootLeft = left_foot;
745  ivStartFootRight = right_foot;
746 
747  ivStartPoseSetUp = true;
748 
749  return true;
750 }
751 
752 
753 bool
754 FootstepPlanner::setStart(float x, float y, float theta)
755 {
756  if (!ivMapPtr)
757  {
758  ROS_ERROR("Distance map hasn't been initialized yet.");
759  return false;
760  }
761 
762  State start(x, y, theta, NOLEG);
763  State foot_left = getFootPose(start, LEFT);
764  State foot_right = getFootPose(start, RIGHT);
765 
766  bool success = setStart(foot_left, foot_right);
767  if (success)
768  ROS_INFO("Start pose set to (%f %f %f)", x, y, theta);
769  else
770  ROS_ERROR("Start pose (%f %f %f) not accessible.", x, y, theta);
771 
772  // publish visualization:
773  geometry_msgs::PoseStamped start_pose;
774  start_pose.pose.position.x = x;
775  start_pose.pose.position.y = y;
776  start_pose.pose.position.z = 0.025;
777  start_pose.pose.orientation = tf::createQuaternionMsgFromYaw(theta);
778  start_pose.header.frame_id = ivMapPtr->getFrameID();
779  start_pose.header.stamp = ros::Time::now();
780  ivStartPoseVisPub.publish(start_pose);
781 
782  return success;
783 }
784 
785 
786 bool
788 {
789  // store old map pointer locally
790  GridMap2DPtr old_map = ivMapPtr;
791  // store new map
792  ivMapPtr.reset();
793  ivMapPtr = map;
794 
795  // check if a previous map and a path existed
796  if (old_map && (bool)ivPath.size())
797  {
798  updateEnvironment(old_map);
799  return true;
800  }
801 
802  // ..otherwise the environment's map can simply be updated
803  ivPlannerEnvironmentPtr->updateMap(map);
804  return false;
805 }
806 
807 
808 void
810 {
811  ROS_INFO("Reseting the planning environment.");
812  // reset environment
813  resetTotally();
814  // set the new map
815  ivPlannerEnvironmentPtr->updateMap(ivMapPtr);
816 
817 
818  // The following is not used any more
819 
820  // Replanning based on old planning info currently disabled
821  // // TODO: handle size changes of the map; currently the planning
822  // // information is reseted
823  //
824  // if (ivPlannerType == "ADPlanner" &&
825  // ivMapPtr->getResolution() == old_map->getResolution() &&
826  // ivMapPtr->size().height == old_map->size().height &&
827  // ivMapPtr->size().width == old_map->size().width)
828  // {
829  // ROS_INFO("Received an updated map => change detection");
830  //
831  // std::vector<State2> changed_states;
832  // cv::Mat changed_cells;
833  //
834  // // get new occupied cells only (0: occupied in binary map)
835  // // changedCells(x,y) = old(x,y) AND NOT(new(x,y))
838  //
839  // // to get all changed cells (new free and occupied) use XOR:
840  // cv::bitwise_xor(old_map->binaryMap(), ivMapPtr->binaryMap(),
841  // changed_cells);
842  //
843  // //inflate by outer foot radius:
844  // cv::bitwise_not(changed_cells, changed_cells); // invert for distanceTransform
845  // cv::Mat changedDistMap = cv::Mat(changed_cells.size(), CV_32FC1);
846  // cv::distanceTransform(changed_cells, changedDistMap,
847  // CV_DIST_L2, CV_DIST_MASK_PRECISE);
848  // double max_foot_radius = sqrt(
849  // pow(std::abs(ivOriginFootShiftX) + ivFootsizeX / 2.0, 2.0) +
850  // pow(std::abs(ivOriginFootShiftY) + ivFootsizeY / 2.0, 2.0))
851  // / ivMapPtr->getResolution();
852  // changed_cells = (changedDistMap <= max_foot_radius); // threshold, also invert back
853  //
854  // // loop over changed cells (now marked with 255 in the mask):
855  // unsigned int num_changed_cells = 0;
856  // double wx, wy;
857  // State2 s;
858  // for (int y = 0; y < changed_cells.rows; ++y)
859  // {
860  // for (int x = 0; x < changed_cells.cols; ++x)
861  // {
862  // if (changed_cells.at<uchar>(x,y) == 255)
863  // {
864  // ++num_changed_cells;
865  // ivMapPtr->mapToWorld(x, y, wx, wy);
866  // s.setX(wx);
867  // s.setY(wy);
868  // // on each grid cell ivNumAngleBins-many planning states
869  // // can be placed (if the resolution of the grid cells is
870  // // the same as of the planning state grid)
871  // for (int theta = 0; theta < ivNumAngleBins; ++theta)
872  // {
873  // s.setTheta(angle_cell_2_state(theta, ivNumAngleBins));
874  // changed_states.push_back(s);
875  // }
876  // }
877  // }
878  // }
879  //
880  // if (num_changed_cells == 0)
881  // {
882  // ROS_INFO("old map equals new map; no replanning necessary");
883  // return;
884  // }
885  //
886  // ROS_INFO("%d changed map cells found", num_changed_cells);
887  // if (num_changed_cells <= ivChangedCellsLimit)
888  // {
889  // // update planer
890  // ROS_INFO("Use old information in new planning taks");
891  //
892  // std::vector<int> neighbour_ids;
893  // if (ivForwardSearch)
894  // ivPlannerEnvironmentPtr->getSuccsOfGridCells(
895  // changed_states, &neighbour_ids);
896  // else
897  // ivPlannerEnvironmentPtr->getPredsOfGridCells(
898  // changed_states, &neighbour_ids);
899  //
900  // boost::shared_ptr<ADPlanner> h =
901  // boost::dynamic_pointer_cast<ADPlanner>(ivPlannerPtr);
902  // h->costs_changed(PlanningStateChangeQuery(neighbour_ids));
903  // }
904  // else
905  // {
906  // ROS_INFO("Reset old information in new planning task");
907  // // reset planner
908  // ivPlannerEnvironmentPtr->reset();
909  // setPlanner();
910  // //ivPlannerPtr->force_planning_from_scratch();
911  // }
912  // }
913  // else
914  // {
915  // ROS_INFO("Reset old information in new planning task");
916  // // reset planner
917  // ivPlannerEnvironmentPtr->reset();
918  // setPlanner();
919  // //ivPlannerPtr->force_planning_from_scratch();
920  // }
921 }
922 
923 
924 State
926 {
927  double shift_x = -sin(robot.getTheta()) * ivFootSeparation / 2.0;
928  double shift_y = cos(robot.getTheta()) * ivFootSeparation / 2.0;
929 
930  double sign = -1.0;
931  if (leg == LEFT)
932  sign = 1.0;
933 
934  return State(robot.getX() + sign * shift_x,
935  robot.getY() + sign * shift_y,
936  robot.getTheta(),
937  leg);
938 }
939 
940 
941 bool
942 FootstepPlanner::pathIsNew(const std::vector<int>& new_path)
943 {
944  if (new_path.size() != ivPlanningStatesIds.size())
945  return true;
946 
947  bool unequal = true;
948  for (unsigned i = 0; i < new_path.size(); ++i)
949  unequal = new_path[i] != ivPlanningStatesIds[i] && unequal;
950 
951  return unequal;
952 }
953 
954 
955 void
957 {
958  visualization_msgs::Marker marker;
959  visualization_msgs::MarkerArray marker_msg;
960 
961  marker.header.stamp = ros::Time::now();
962  marker.header.frame_id = ivMapPtr->getFrameID();
963 
964 
965  if (num_footsteps < 1)
966  num_footsteps = ivLastMarkerMsgSize;
967 
968  for (unsigned i = 0; i < num_footsteps; ++i)
969  {
970  marker.ns = ivMarkerNamespace;
971  marker.id = i;
972  marker.action = visualization_msgs::Marker::DELETE;
973 
974  marker_msg.markers.push_back(marker);
975  }
976 
977  ivFootstepPathVisPub.publish(marker_msg);
978 }
979 
980 
981 void
983 {
985  {
986  sensor_msgs::PointCloud cloud_msg;
987  geometry_msgs::Point32 point;
988  std::vector<geometry_msgs::Point32> points;
989 
990  State s;
992  for(state_id_it = ivPlannerEnvironmentPtr->getExpandedStatesStart();
993  state_id_it != ivPlannerEnvironmentPtr->getExpandedStatesEnd();
994  ++state_id_it)
995  {
996  point.x = cell_2_state(state_id_it->first,
998  point.y = cell_2_state(state_id_it->second,
1000  point.z = 0.01;
1001  points.push_back(point);
1002  }
1003  cloud_msg.header.stamp = ros::Time::now();
1004  cloud_msg.header.frame_id = ivMapPtr->getFrameID();
1005 
1006  cloud_msg.points = points;
1007 
1008  ivExpandedStatesVisPub.publish(cloud_msg);
1009  }
1010 }
1011 
1012 
1013 void
1015 {
1016  if (getPathSize() == 0)
1017  {
1018  ROS_INFO("no path has been extracted yet");
1019  return;
1020  }
1021 
1023 
1024  visualization_msgs::Marker marker;
1025  visualization_msgs::MarkerArray broadcast_msg;
1026  std::vector<visualization_msgs::Marker> markers;
1027 
1028  int markers_counter = 0;
1029 
1030  marker.header.stamp = ros::Time::now();
1031  marker.header.frame_id = ivMapPtr->getFrameID();
1032 
1033  // add the missing start foot to the publish vector for visualization:
1034  if (ivPath.front().getLeg() == LEFT)
1036  else
1038  marker.id = markers_counter++;
1039  markers.push_back(marker);
1040 
1041  // add the footsteps of the path to the publish vector
1042  for(state_iter_t path_iter = getPathBegin(); path_iter != getPathEnd();
1043  ++path_iter)
1044  {
1045  footPoseToMarker(*path_iter, &marker);
1046  marker.id = markers_counter++;
1047  markers.push_back(marker);
1048  }
1049 
1050  broadcast_msg.markers = markers;
1051  ivLastMarkerMsgSize = markers.size();
1052 
1053  ivFootstepPathVisPub.publish(broadcast_msg);
1054 }
1055 
1056 
1057 void
1059 {
1061  sensor_msgs::PointCloud cloud_msg;
1062  geometry_msgs::Point32 point;
1063  std::vector<geometry_msgs::Point32> points;
1064  visualization_msgs::Marker marker;
1065  visualization_msgs::MarkerArray broadcast_msg;
1066  std::vector<visualization_msgs::Marker> markers;
1067 
1068  marker.header.stamp = ros::Time::now();
1069  marker.header.frame_id = ivMapPtr->getFrameID();
1070 
1071  State s;
1073  for(state_id_iter = ivPlannerEnvironmentPtr->getRandomStatesStart();
1074  state_id_iter != ivPlannerEnvironmentPtr->getRandomStatesEnd();
1075  ++state_id_iter)
1076  {
1077  if (!ivPlannerEnvironmentPtr->getState(*state_id_iter, &s))
1078  {
1079  ROS_WARN("Could not get random state %d", *state_id_iter);
1080  }
1081  else
1082  {
1083  point.x = s.getX();
1084  point.y = s.getY();
1085  point.z = 0.01;
1086  points.push_back(point);
1087  }
1088  }
1089  cloud_msg.header.stamp = ros::Time::now();
1090  cloud_msg.header.frame_id = ivMapPtr->getFrameID();
1091 
1092  cloud_msg.points = points;
1093 
1094  ivRandomStatesVisPub.publish(cloud_msg);
1095  }
1096 }
1097 
1098 
1099 void
1101 {
1102  if (getPathSize() == 0)
1103  {
1104  ROS_INFO("no path has been extracted yet");
1105  return;
1106  }
1107 
1108  nav_msgs::Path path_msg;
1109  geometry_msgs::PoseStamped state;
1110 
1111  state.header.stamp = ros::Time::now();
1112  state.header.frame_id = ivMapPtr->getFrameID();
1113 
1114  state_iter_t path_iter;
1115  for(path_iter = getPathBegin(); path_iter != getPathEnd(); ++path_iter)
1116  {
1117  state.pose.position.x = path_iter->getX();
1118  state.pose.position.y = path_iter->getY();
1119  path_msg.poses.push_back(state);
1120  }
1121 
1122  path_msg.header = state.header;
1123  ivPathVisPub.publish(path_msg);
1124 }
1125 
1126 
1127 void
1129  visualization_msgs::Marker* marker)
1130 {
1131  marker->header.stamp = ros::Time::now();
1132  marker->header.frame_id = ivMapPtr->getFrameID();
1133  marker->ns = ivMarkerNamespace;
1134  marker->type = visualization_msgs::Marker::CUBE;
1135  marker->action = visualization_msgs::Marker::ADD;
1136 
1137  float cos_theta = cos(foot_pose.getTheta());
1138  float sin_theta = sin(foot_pose.getTheta());
1139  float x_shift = cos_theta * ivEnvironmentParams.foot_origin_shift_x -
1141  float y_shift;
1142  if (foot_pose.getLeg() == LEFT)
1143  y_shift = sin_theta * ivEnvironmentParams.foot_origin_shift_x +
1145  else // leg == RLEG
1146  y_shift = sin_theta * ivEnvironmentParams.foot_origin_shift_x -
1148  marker->pose.position.x = foot_pose.getX() + x_shift;
1149  marker->pose.position.y = foot_pose.getY() + y_shift;
1150  marker->pose.position.z = ivEnvironmentParams.footsize_z / 2.0;
1152  marker->pose.orientation);
1153 
1154  marker->scale.x = ivEnvironmentParams.footsize_x; // - 0.01;
1155  marker->scale.y = ivEnvironmentParams.footsize_y; // - 0.01;
1156  marker->scale.z = ivEnvironmentParams.footsize_z;
1157 
1158  // TODO: make color configurable?
1159  if (foot_pose.getLeg() == RIGHT)
1160  {
1161  marker->color.r = 0.0f;
1162  marker->color.g = 1.0f;
1163  }
1164  else // leg == LEFT
1165  {
1166  marker->color.r = 1.0f;
1167  marker->color.g = 0.0f;
1168  }
1169  marker->color.b = 0.0;
1170  marker->color.a = 0.6;
1171 
1172  marker->lifetime = ros::Duration();
1173 }
1174 }
double getTheta() const
Definition: State.h:48
double cell_2_state(int value, double cell_size)
Calculate the respective (continuous) state value for a cell. (Should be used to get a State from a d...
Definition: helper.h:122
bool setGoal(const State &left_foot, const State &right_foot)
Sets the goal pose as two feet (left / right)
boost::shared_ptr< Heuristic > heuristic
void publish(const boost::shared_ptr< M > &message) const
std::vector< int > ivPlanningStatesIds
f
bool planFeetService(humanoid_nav_msgs::PlanFootstepsBetweenFeet::Request &req, humanoid_nav_msgs::PlanFootstepsBetweenFeet::Response &resp)
Service handle to plan footsteps.
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.
void clearFootstepPathVis(unsigned num_footsteps=0)
Clear the footstep path visualization from a previous planning task.
int size() const
A class defining a footstep planner environment for humanoid robots used by the SBPL to perform plann...
Determining the heuristic value by calculating a 2D path from each grid cell of the map to the goal a...
static double getYaw(const Quaternion &bt_q)
XmlRpcServer s
environment_params ivEnvironmentParams
Planning parameters.
void goalPoseCallback(const geometry_msgs::PoseStampedConstPtr &goal_pose)
Callback to set the goal pose as a robot pose centered between two feet. If the start pose has been s...
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
boost::shared_ptr< GridMap2D > GridMap2DPtr
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancy_map)
Callback to set the map.
double getX() const
Definition: State.h:46
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
Determining the heuristic value by the euclidean distance between two states, the expected step costs...
Definition: Heuristic.h:82
boost::shared_ptr< SBPLPlanner > ivPlannerPtr
void startPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &start_pose)
Callback to set the start pose as a robot pose centered between two feet. If the goal pose has been s...
void updateEnvironment(const gridmap_2d::GridMap2DPtr old_map)
Updates the environment in case of a changed map.
static Quaternion createQuaternionFromYaw(double yaw)
boost::shared_ptr< FootstepPlannerEnvironment > ivPlannerEnvironmentPtr
state_iter_t getPathBegin() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double getY() const
Definition: State.h:47
int disc_val(double length, double cell_size)
Discretize a (continuous) value into cell size.
Definition: helper.h:130
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
bool pathIsNew(const std::vector< int > &new_path)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< const PathCostHeuristic > ivPathCostHeuristicPtr
Determining the heuristic value by the euclidean distance between two states.
Definition: Heuristic.h:64
void reset()
Reset the previous planning information.
void extractFootstepsSrv(std::vector< humanoid_nav_msgs::StepTarget > &footsteps) const
helper to create service response
std::vector< std::pair< int, int > > step_range
Defines the area of performable (discrete) steps.
bool run()
Starts the planning task in the underlying SBPL.
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
static WallTime now()
static const int cvMmScale
Used to scale continuous values in meter to discrete values in mm.
bool getParam(const std::string &key, std::string &s) const
State getFootPose(const State &robot, Leg side)
Returns the foot pose of a leg for a given robot pose.
bool planService(humanoid_nav_msgs::PlanFootsteps::Request &req, humanoid_nav_msgs::PlanFootsteps::Response &resp)
Service handle to plan footsteps.
static Time now()
A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to t...
Definition: Footstep.h:38
#define ROS_ERROR_STREAM(args)
std::vector< State >::const_iterator state_iter_t
Leg getLeg() const
Definition: State.h:49
#define ROS_ERROR(...)
void footPoseToMarker(const State &footstep, visualization_msgs::Marker *marker)
Generates a visualization msgs for a foot pose.
void resetTotally()
Reset and reinitialize the environment.
void setPlanner()
Sets the planning algorithm used by SBPL.
bool setStart(const geometry_msgs::PoseStampedConstPtr start_pose)
Sets the start pose as a robot pose centered between two feet.
int ivChangedCellsLimit
If limit of changed cells is reached the planner starts a new task from the scratch.
gridmap_2d::GridMap2DPtr ivMapPtr
bool extractPath(const std::vector< int > &state_ids)
Extracts the path (list of foot poses) from a list of state IDs calculated by the SBPL...


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