22 #include <humanoid_nav_msgs/ClipFootstep.h> 32 : ivStartPoseSetUp(false),
33 ivGoalPoseSetUp(false),
34 ivLastMarkerMsgSize(0),
44 sensor_msgs::PointCloud>(
"expanded_states", 1);
46 sensor_msgs::PointCloud>(
"random_states", 1);
48 visualization_msgs::MarkerArray>(
"footsteps_array", 1);
50 nav_msgs::Path>(
"heuristic_path", 1);
53 geometry_msgs::PoseStamped>(
"start", 1);
55 std::string heuristic_type;
56 double diff_angle_cost;
60 nh_private.
param(
"heuristic_type", heuristic_type,
61 std::string(
"EuclideanHeuristic"));
64 nh_private.
param(
"accuracy/collision_check",
68 nh_private.
param(
"accuracy/num_angle_bins",
72 nh_private.
param(
"diff_angle_cost", diff_angle_cost, 0.0);
91 nh_private.
param(
"foot/origin_shift/x",
94 nh_private.
param(
"foot/origin_shift/y",
99 nh_private.
param(
"foot/max/step/theta",
102 nh_private.
param(
"foot/max/inverse/step/x",
105 nh_private.
param(
"foot/max/inverse/step/y",
108 nh_private.
param(
"foot/max/inverse/step/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);
120 ROS_ERROR(
"Error reading footsteps/x from config file.");
122 ROS_ERROR(
"Error reading footsteps/y from config file.");
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)
130 ROS_ERROR(
"Footstep parameterization has different sizes for x/y/theta. " 136 double max_step_width = 0;
137 for(
int i=0; i < footsteps_x.
size(); ++i)
139 double x = (double)footsteps_x[i];
140 double y = (double)footsteps_y[i];
141 double theta = (double)footsteps_theta[i];
149 double cur_step_width = sqrt(x*x + y*y);
151 if (cur_step_width > max_step_width)
152 max_step_width = cur_step_width;
158 nh_private.
getParam(
"step_range/x", step_range_x);
159 nh_private.
getParam(
"step_range/y", step_range_y);
161 ROS_ERROR(
"Error reading footsteps/x from config file.");
163 ROS_ERROR(
"Error reading footsteps/y from config file.");
164 if (step_range_x.
size() != step_range_y.
size())
166 ROS_ERROR(
"Step range points have different size. Exit!");
176 for (
int i=0; i < step_range_x.
size(); ++i)
178 x = (double)step_range_x[i];
179 y = (double)step_range_y[i];
193 if (heuristic_type ==
"EuclideanHeuristic")
198 ROS_INFO(
"FootstepPlanner heuristic: euclidean distance");
200 else if(heuristic_type ==
"EuclStepCostHeuristic")
208 ROS_INFO(
"FootstepPlanner heuristic: euclidean distance with step costs");
210 else if (heuristic_type ==
"PathCostHeuristic")
213 double foot_incircle =
218 assert(foot_incircle > 0.0);
227 ROS_INFO(
"FootstepPlanner heuristic: 2D path euclidean distance with step " 308 bool path_existed = (bool)
ivPath.size();
310 MDPConfig mdp_config;
311 std::vector<int> solution_state_ids;
325 std::vector<int> changed_edges;
326 changed_edges.push_back(mdp_config.startstateid);
330 ad_planner->update_preds_of_changededges(&changed_edges);
334 if (
ivPlannerPtr->set_start(mdp_config.startstateid) == 0)
339 if (
ivPlannerPtr->set_goal(mdp_config.goalstateid) == 0)
348 ROS_INFO(
"Start planning (max time: %f, initial eps: %f (%f))\n",
358 catch (
const SBPL_Exception& e)
365 bool path_is_new =
pathIsNew(solution_state_ids);
366 if (ret && solution_state_ids.size() > 0)
369 ROS_WARN(
"Solution found by SBPL is the same as the old solution. This could indicate that replanning failed.");
371 ROS_INFO(
"Solution of size %zu found after %f s",
372 solution_state_ids.size(),
377 ROS_INFO(
"Expanded states: %i total / %i new",
416 std::vector<int>::const_iterator state_ids_iter = state_ids.begin();
437 ivPath.push_back(start_left);
440 for(; state_ids_iter < state_ids.end(); ++state_ids_iter)
480 ROS_INFO(
"Resetting planner and environment");
496 ROS_ERROR(
"FootstepPlanner has no map for planning yet.");
501 ROS_ERROR(
"FootstepPlanner has not set the start and/or goal pose " 525 const geometry_msgs::PoseStampedConstPtr
goal)
527 return plan(start->pose.position.x, start->pose.position.y,
529 goal->pose.position.x, goal->pose.position.y,
536 float goal_x,
float goal_y,
float goal_theta)
538 if (!(
setStart(start_x, start_y, start_theta) &&
539 setGoal(goal_x, goal_y, goal_theta)))
550 humanoid_nav_msgs::PlanFootsteps::Response &
resp)
552 bool result =
plan(req.start.x, req.start.y, req.start.theta,
553 req.goal.x, req.goal.y, req.goal.theta);
561 resp.result = result;
571 humanoid_nav_msgs::PlanFootstepsBetweenFeet::Response &
resp)
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));
579 bool result =
plan(
false);
587 resp.result = result;
596 humanoid_nav_msgs::StepTarget foot;
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;
609 ROS_ERROR(
"Footstep pose at (%f, %f, %f) is set to NOLEG!",
610 path_iter->getX(), path_iter->getY(),
611 path_iter->getTheta());
615 footsteps.push_back(foot);
623 const geometry_msgs::PoseStampedConstPtr& goal_pose)
639 const geometry_msgs::PoseWithCovarianceStampedConstPtr& start_pose)
641 if (
setStart(start_pose->pose.pose.position.x,
642 start_pose->pose.pose.position.y,
643 tf::getYaw(start_pose->pose.pose.orientation)))
656 const nav_msgs::OccupancyGridConstPtr& occupancy_map)
673 return setGoal(goal_pose->pose.position.x,
674 goal_pose->pose.position.y,
684 ROS_ERROR(
"Distance map hasn't been initialized yet.");
695 ROS_ERROR(
"Goal pose at (%f %f %f) not accessible.", x, y, theta);
703 ROS_INFO(
"Goal pose set to (%f %f %f)", x, y, theta);
729 return setStart(start_pose->pose.position.x,
730 start_pose->pose.position.y,
758 ROS_ERROR(
"Distance map hasn't been initialized yet.");
766 bool success =
setStart(foot_left, foot_right);
768 ROS_INFO(
"Start pose set to (%f %f %f)", x, y, theta);
770 ROS_ERROR(
"Start pose (%f %f %f) not accessible.", x, y, theta);
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;
778 start_pose.header.frame_id =
ivMapPtr->getFrameID();
796 if (old_map && (
bool)
ivPath.size())
811 ROS_INFO(
"Reseting the planning environment.");
934 return State(robot.
getX() + sign * shift_x,
935 robot.
getY() + sign * shift_y,
948 for (
unsigned i = 0; i < new_path.size(); ++i)
958 visualization_msgs::Marker marker;
959 visualization_msgs::MarkerArray marker_msg;
962 marker.header.frame_id =
ivMapPtr->getFrameID();
965 if (num_footsteps < 1)
968 for (
unsigned i = 0; i < num_footsteps; ++i)
972 marker.action = visualization_msgs::Marker::DELETE;
974 marker_msg.markers.push_back(marker);
986 sensor_msgs::PointCloud cloud_msg;
987 geometry_msgs::Point32 point;
988 std::vector<geometry_msgs::Point32> points;
1001 points.push_back(point);
1004 cloud_msg.header.frame_id =
ivMapPtr->getFrameID();
1006 cloud_msg.points = points;
1018 ROS_INFO(
"no path has been extracted yet");
1024 visualization_msgs::Marker marker;
1025 visualization_msgs::MarkerArray broadcast_msg;
1026 std::vector<visualization_msgs::Marker> markers;
1028 int markers_counter = 0;
1031 marker.header.frame_id =
ivMapPtr->getFrameID();
1038 marker.id = markers_counter++;
1039 markers.push_back(marker);
1046 marker.id = markers_counter++;
1047 markers.push_back(marker);
1050 broadcast_msg.markers = markers;
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;
1069 marker.header.frame_id =
ivMapPtr->getFrameID();
1079 ROS_WARN(
"Could not get random state %d", *state_id_iter);
1086 points.push_back(point);
1090 cloud_msg.header.frame_id =
ivMapPtr->getFrameID();
1092 cloud_msg.points = points;
1104 ROS_INFO(
"no path has been extracted yet");
1108 nav_msgs::Path path_msg;
1109 geometry_msgs::PoseStamped state;
1112 state.header.frame_id =
ivMapPtr->getFrameID();
1117 state.pose.position.x = path_iter->getX();
1118 state.pose.position.y = path_iter->getY();
1119 path_msg.poses.push_back(state);
1122 path_msg.header = state.header;
1129 visualization_msgs::Marker* marker)
1132 marker->header.frame_id =
ivMapPtr->getFrameID();
1134 marker->type = visualization_msgs::Marker::CUBE;
1135 marker->action = visualization_msgs::Marker::ADD;
1137 float cos_theta = cos(foot_pose.
getTheta());
1138 float sin_theta = sin(foot_pose.
getTheta());
1148 marker->pose.position.x = foot_pose.
getX() + x_shift;
1149 marker->pose.position.y = foot_pose.
getY() + y_shift;
1152 marker->pose.orientation);
1161 marker->color.r = 0.0f;
1162 marker->color.g = 1.0f;
1166 marker->color.r = 1.0f;
1167 marker->color.g = 0.0f;
1169 marker->color.b = 0.0;
1170 marker->color.a = 0.6;
void publish(const boost::shared_ptr< M > &message) const
static double getYaw(const Quaternion &bt_q)
Type const & getType() const
boost::shared_ptr< GridMap2D > GridMap2DPtr
static Quaternion createQuaternionFromYaw(double yaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)