Exemple #1
0
 double footstepHeuristicStraightRotation(
   SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph)
 {
   FootstepState::Ptr state = node->getState();
   FootstepState::Ptr goal = graph->getGoal(state->getLeg());
   Eigen::Affine3f transform = state->getPose().inverse() * goal->getPose();
   return (std::abs(transform.translation().norm() / graph->maxSuccessorDistance()) +
              std::abs(Eigen::AngleAxisf(transform.rotation()).angle()) / graph->maxSuccessorRotation());
 }
Exemple #2
0
 double footstepHeuristicStraight(
   SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph)
 {
   FootstepState::Ptr state = node->getState();
   FootstepState::Ptr goal = graph->getGoal(state->getLeg());
   Eigen::Vector3f state_pos(state->getPose().translation());
   Eigen::Vector3f goal_pos(goal->getPose().translation());
   return (std::abs((state_pos - goal_pos).norm() / graph->maxSuccessorDistance()));
 }
  double footstepHeuristicFollowPathLine(
    SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph)
  {
    FootstepState::Ptr state = node->getState();
    FootstepState::Ptr goal = graph->getGoal(state->getLeg());

    Eigen::Vector3f goal_pos(goal->getPose().translation());
    Eigen::Vector3f state_pos(state->getPose().translation());
    Eigen::Vector3f state_mid_pos;
    if (state->getLeg() == jsk_footstep_msgs::Footstep::LEFT) {
      Eigen::Vector3f p(0, -0.1, 0);
      state_mid_pos = state->getPose() * p;
    } else { // Right
      Eigen::Vector3f p(0, 0.1, 0);
      state_mid_pos = state->getPose() * p;
    }
    double dist, to_goal, alp;
    int idx;
    Eigen::Vector3f foot;
    dist = graph->heuristic_path_->distanceWithInfo(state_mid_pos, foot, to_goal, idx, alp);

    //jsk_recognition_utils::FiniteLine::Ptr ln = graph->heuristic_path_->at(idx);
    Eigen::Vector3f dir = graph->heuristic_path_->getDirection(idx);

    Eigen::Quaternionf path_foot_rot;
    path_foot_rot.setFromTwoVectors(state->getPose().matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX(),
                                    dir);
    double path_foot_theta = acos(path_foot_rot.w()) * 2;
    if (path_foot_theta > M_PI) {
      path_foot_theta = 2.0 * M_PI - path_foot_theta;
      // foot_theta : [0, M_PI]
    }

    double step_cost = to_goal / graph->maxSuccessorDistance();
    double follow_cost = dist / 0.02; // ???
    double path_foot_rot_cost = path_foot_theta / graph->maxSuccessorRotation();

    Eigen::Vector3f goal_diff = goal_pos - state_pos;
    Eigen::Quaternionf goal_foot_rot;
    goal_foot_rot.setFromTwoVectors(state->getPose().matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX(),
                                    goal->getPose().matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX());
    double goal_foot_theta = acos(goal_foot_rot.w()) * 2;
    if (goal_foot_theta > M_PI) {
      goal_foot_theta = 2.0 * M_PI - goal_foot_theta;
    }
    double goal_foot_rot_cost = goal_foot_theta / graph->maxSuccessorRotation();

    //return step_cost + follow_cost + (4.0 * goal_foot_rot_cost) + (0.5 * path_foot_rot_cost);
    return 2*(step_cost + follow_cost + (0.5 * path_foot_rot_cost));
  }
  double footstepHeuristicStepCost(
    SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph,
    double first_rotation_weight,
    double second_rotation_weight)
  {
    FootstepState::Ptr state = node->getState();
    FootstepState::Ptr goal = graph->getGoal(state->getLeg());
    Eigen::Vector3f goal_pos(goal->getPose().translation());
    Eigen::Vector3f diff_pos(goal_pos - state->getPose().translation());
    diff_pos[2] = 0.0;          // Ignore z distance
    Eigen::Quaternionf first_rot;
    // Eigen::Affine3f::rotation is too slow because it calls SVD decomposition
    first_rot.setFromTwoVectors(state->getPose().matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX(),
                                diff_pos.normalized());

    Eigen::Quaternionf second_rot;
    second_rot.setFromTwoVectors(diff_pos.normalized(),
                                 goal->getPose().matrix().block<3, 3>(0, 0) * Eigen::Vector3f::UnitX());
    // is it correct??
    double first_theta = acos(first_rot.w()) * 2;
    double second_theta = acos(second_rot.w()) * 2;
    if (isnan(first_theta)) {
      first_theta = 0;
    }
    if (isnan(second_theta)) {
      second_theta = 0;
    }
    // acos := [0, M_PI]
    if (first_theta > M_PI) {
      first_theta = 2.0 * M_PI - first_theta;
    }
    if (second_theta > M_PI) {
      second_theta = 2.0 * M_PI - second_theta;
    }
    //return (Eigen::Vector2f(diff_pos[0], diff_pos[1]).norm() / graph->maxSuccessorDistance()) + std::abs(diff_pos[2]) / 0.2 +
    return (diff_pos.norm() / graph->maxSuccessorDistance()) + std::abs(diff_pos[2]) / 0.2 + 
      (first_theta * first_rotation_weight + second_theta * second_rotation_weight) / graph->maxSuccessorRotation();
  }
void plan(const Eigen::Affine3f& goal_center,
          FootstepGraph::Ptr graph, ros::Publisher& pub_path,
          ros::Publisher& pub_goal,
          Eigen::Vector3f footstep_size)
{
  FootstepState::Ptr left_goal(new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
                                                 goal_center * Eigen::Translation3f(0, 0.1, 0),
                                                 footstep_size,
                                                 resolution));
  FootstepState::Ptr right_goal(new FootstepState(jsk_footstep_msgs::Footstep::RIGHT,
                                                  goal_center * Eigen::Translation3f(0, -0.1, 0),
                                                  footstep_size,
                                                  resolution));

  jsk_footstep_msgs::FootstepArray ros_goal;
  ros_goal.header.frame_id = "odom";
  ros_goal.header.stamp = ros::Time::now();
  ros_goal.footsteps.push_back(*left_goal->toROSMsg());
  ros_goal.footsteps.push_back(*right_goal->toROSMsg());
  pub_goal.publish(ros_goal);
    
  graph->setGoalState(left_goal, right_goal);
  //AStarSolver<FootstepGraph> solver(graph);
  FootstepAStarSolver<FootstepGraph> solver(graph, 100, 100, 100);
  //solver.setHeuristic(&footstepHeuristicStraight);
  //solver.setHeuristic(&footstepHeuristicStraightRotation);
  solver.setHeuristic(boost::bind(&footstepHeuristicStepCost, _1, _2, 1.0, 0.1));
  solver.setProfileFunction(&profile);
  ros::WallTime start_time = ros::WallTime::now();
  std::vector<SolverNode<FootstepState, FootstepGraph>::Ptr> path = solver.solve();
  ros::WallTime end_time = ros::WallTime::now();
  std::cout << "took " << (end_time - start_time).toSec() << " sec" << std::endl;
  std::cout << "path: " << path.size() << std::endl;
  jsk_footstep_msgs::FootstepArray ros_path;
  ros_path.header.frame_id = "odom";
  ros_path.header.stamp = ros::Time::now();
  for (size_t i = 0; i < path.size(); i++) {
    ros_path.footsteps.push_back(*path[i]->getState()->toROSMsg());
  }
  pub_path.publish(ros_path);

}
int main(int argc, char** argv)
{
  ros::init(argc, argv, "foootstep_planning_2d");
  ros::NodeHandle nh("~");
  ros::Publisher pub_start = nh.advertise<jsk_footstep_msgs::FootstepArray>("start", 1, true);
  pub_goal = nh.advertise<jsk_footstep_msgs::FootstepArray>("goal", 1, true);
  pub_path = nh.advertise<jsk_footstep_msgs::FootstepArray>("path", 1, true);
  pub_text = nh.advertise<jsk_rviz_plugins::OverlayText>("text", 1, true);
  boost::mt19937 rng( static_cast<unsigned long>(time(0)) );
  boost::uniform_real<> xyrange(-3.0,3.0);
  boost::variate_generator< boost::mt19937, boost::uniform_real<> > pos_rand(rng, xyrange);
  boost::uniform_real<> trange(0, 2 * M_PI);
  boost::variate_generator< boost::mt19937, boost::uniform_real<> > rot_rand(rng, trange);

  graph.reset(new FootstepGraph(resolution));
  //graph->setProgressPublisher(nh, "progress");
  // set successors
  std::vector<Eigen::Affine3f> successors;
  successors.push_back(affineFromXYYaw(0, -0.2, 0));
  successors.push_back(affineFromXYYaw(0, -0.3, 0));
  successors.push_back(affineFromXYYaw(0, -0.15, 0));
  successors.push_back(affineFromXYYaw(0.2, -0.2, 0));
  successors.push_back(affineFromXYYaw(0.25, -0.2, 0));
  successors.push_back(affineFromXYYaw(0.1, -0.2, 0));
  successors.push_back(affineFromXYYaw(-0.1, -0.2, 0));
  successors.push_back(affineFromXYYaw(0, -0.2, 0.17));
  successors.push_back(affineFromXYYaw(0, -0.3, 0.17));
  successors.push_back(affineFromXYYaw(0.2, -0.2, 0.17));
  successors.push_back(affineFromXYYaw(0.25, -0.2, 0.17));
  successors.push_back(affineFromXYYaw(0.1, -0.2, 0.17));
  successors.push_back(affineFromXYYaw(0, -0.2, -0.17));
  successors.push_back(affineFromXYYaw(0, -0.3, -0.17));
  successors.push_back(affineFromXYYaw(0.2, -0.2, -0.17));
  successors.push_back(affineFromXYYaw(0.25, -0.2, -0.17));
  successors.push_back(affineFromXYYaw(0.1, -0.2, -0.17));
  FootstepState::Ptr start(new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
                                             Eigen::Affine3f::Identity(),
                                             footstep_size,
                                             resolution));
  graph->setStartState(start);
  graph->setBasicSuccessors(successors);
  jsk_footstep_msgs::FootstepArray ros_start;
  ros_start.header.frame_id = "odom";
  ros_start.header.stamp = ros::Time::now();
  ros_start.footsteps.push_back(*start->toROSMsg());
  pub_start.publish(ros_start);
  interactive_markers::InteractiveMarkerServer server("footstep_projection_demo");

  visualization_msgs::InteractiveMarker int_marker;
  int_marker.header.frame_id = "/odom";
  int_marker.header.stamp=ros::Time::now();
  int_marker.name = "footstep marker";

  visualization_msgs::InteractiveMarkerControl control;

  control.orientation.w = 1;
  control.orientation.x = 1;
  control.orientation.y = 0;
  control.orientation.z = 0;
  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
  // int_marker.controls.push_back(control);
  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
  int_marker.controls.push_back(control);

  control.orientation.w = 1;
  control.orientation.x = 0;
  control.orientation.y = 1;
  control.orientation.z = 0;
  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
  int_marker.controls.push_back(control);
  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
  // int_marker.controls.push_back(control);

  control.orientation.w = 1;
  control.orientation.x = 0;
  control.orientation.y = 0;
  control.orientation.z = 1;
  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
  // int_marker.controls.push_back(control);
  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
  int_marker.controls.push_back(control);
  server.insert(int_marker, &processFeedback);
  server.applyChanges();
  //plan(Eigen::Affine3f::Identity() * Eigen::Translation3f(3, 3, 0), graph, pub_path, pub_goal, footstep_size);
  ros::spin();
  return 0;
}