コード例 #1
0
  bool FootstepGraph::isGoal(StatePtr state)
  {
    FootstepState::Ptr goal = getGoal(state->getLeg());
    if (publish_progress_) {
      jsk_footstep_msgs::FootstepArray msg;
      msg.header.frame_id = "odom"; // TODO fixed frame_id
      msg.header.stamp = ros::Time::now();
      msg.footsteps.push_back(*state->toROSMsg());
      pub_progress_.publish(msg);
    }
    Eigen::Affine3f pose = state->getPose();
    Eigen::Affine3f goal_pose = goal->getPose();
    Eigen::Affine3f transformation = pose.inverse() * goal_pose;

    if ((parameters_.goal_pos_thr > transformation.translation().norm()) &&
        (parameters_.goal_rot_thr > std::abs(Eigen::AngleAxisf(transformation.rotation()).angle()))) {
      // check collision
      if (state->getLeg() == jsk_footstep_msgs::Footstep::LEFT) {
        if (right_goal_state_->crossCheck(state)) {
          return true;
        }
      } else if (state->getLeg() == jsk_footstep_msgs::Footstep::RIGHT) {
        if (left_goal_state_->crossCheck(state)) {
          return true;
        }
      }
    }
    return false;
  }
コード例 #2
0
ファイル: footstep_graph.cpp プロジェクト: iory/jsk_control
 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());
 }
コード例 #3
0
ファイル: footstep_graph.cpp プロジェクト: iory/jsk_control
 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()));
 }
コード例 #4
0
ファイル: footstep_graph.cpp プロジェクト: iory/jsk_control
 bool FootstepGraph::isGoal(StatePtr state)
 {
   FootstepState::Ptr goal = getGoal(state->getLeg());
   if (publish_progress_) {
     jsk_footstep_msgs::FootstepArray msg;
     msg.header.frame_id = "odom";
     msg.header.stamp = ros::Time::now();
     msg.footsteps.push_back(*state->toROSMsg());
     pub_progress_.publish(msg);
   }
   Eigen::Affine3f pose = state->getPose();
   Eigen::Affine3f goal_pose = goal->getPose();
   Eigen::Affine3f transformation = pose.inverse() * goal_pose;
   return (pos_goal_thr_ > transformation.translation().norm()) &&
     (rot_goal_thr_ > std::abs(Eigen::AngleAxisf(transformation.rotation()).angle()));
 }
コード例 #5
0
 bool TransitionLimitXYZRPY::check(FootstepState::Ptr from,
                                   FootstepState::Ptr to) const
 {
   // from * trans = to
   const Eigen::Affine3f diff = to->getPose() * from->getPose().inverse();
   const Eigen::Vector3f diff_pos(diff.translation());
   if (std::abs(diff_pos[0]) < x_max_ &&
       std::abs(diff_pos[1]) < y_max_ &&
       std::abs(diff_pos[2]) < z_max_) {
     float roll, pitch, yaw;
     pcl::getEulerAngles(diff, roll, pitch, yaw);
     return (std::abs(roll) < roll_max_ &&
             std::abs(pitch) < pitch_max_ &&
             std::abs(yaw) < yaw_max_);
   }
   else {
     return false;
   }
 }
コード例 #6
0
  std::vector<FootstepState::Ptr>
  FootstepGraph::localMoveFootstepState(FootstepState::Ptr in)
  {
    std::vector<FootstepState::Ptr> moved_states;
    moved_states.reserve((2*parameters_.local_move_x_num + 1)*(2*parameters_.local_move_y_num + 1)*(2*parameters_.local_move_theta_num +1) - 1);
    int x_num     = parameters_.local_move_x_num;
    int y_num     = parameters_.local_move_y_num;
    int theta_num = parameters_.local_move_theta_num;
    if(x_num == 0)     x_num = 1;
    if(y_num == 0)     y_num = 1;
    if(theta_num == 0) theta_num = 1;

    double move_x = parameters_.local_move_x;
    double move_y = parameters_.local_move_y;
    double move_t = parameters_.local_move_theta;
    double offset_x = parameters_.local_move_x_offset;
    double offset_y = (in->getLeg() == jsk_footstep_msgs::Footstep::LEFT) ?
      parameters_.local_move_y_offset : - parameters_.local_move_y_offset;
    double offset_t = parameters_.local_move_theta_offset;

    bool have_offset = ((offset_x != 0.0) || (offset_y != 0.0) || (offset_t != 0.0));
    for (int xi = - parameters_.local_move_x_num; xi <= parameters_.local_move_x_num; xi++) {
      for (int yi = - parameters_.local_move_y_num; yi <= parameters_.local_move_y_num; yi++) {
        for (int thetai = - parameters_.local_move_theta_num; thetai <= parameters_.local_move_theta_num; thetai++) {
          if ( have_offset || (xi != 0) || (yi != 0) || (thetai != 0) ) {
            Eigen::Affine3f trans(Eigen::Translation3f((move_x / x_num * xi) + offset_x,
                                                       (move_y / y_num * yi) + offset_y,
                                                       0)
                                  * Eigen::AngleAxisf((move_t / theta_num * thetai) + offset_t,
                                                      Eigen::Vector3f::UnitZ()));
            moved_states.push_back(
                                   FootstepState::Ptr(new FootstepState(in->getLeg(),
                                                                        in->getPose() * trans,
                                                                        in->getDimensions(),
                                                                        in->getResolution())));
          }
        }
      }
    }
    return moved_states;
  }
コード例 #7
0
ファイル: footstep_graph.cpp プロジェクト: iory/jsk_control
 std::vector<FootstepState::Ptr>
 FootstepGraph::localMoveFootstepState(FootstepState::Ptr in)
 {
   std::vector<FootstepState::Ptr> moved_states;
   moved_states.reserve(local_move_x_num_ * local_move_y_num_ * local_move_theta_num_ * 8);
   for (size_t xi = - local_move_x_num_; xi <= local_move_x_num_; xi++) {
     for (size_t yi = - local_move_y_num_; yi <= local_move_y_num_; yi++) {
       for (size_t thetai = - local_move_theta_num_; thetai <= local_move_theta_num_; thetai++) {
         Eigen::Affine3f trans(Eigen::Translation3f(local_move_x_ / local_move_x_num_ * xi,
                                                    local_move_y_ / local_move_y_num_ * yi,
                                                    0)
                               * Eigen::AngleAxisf(local_move_theta_ / local_move_theta_num_ * thetai,
                                                   Eigen::Vector3f::UnitZ()));
         moved_states.push_back(
           FootstepState::Ptr(new FootstepState(in->getLeg(),
                                                in->getPose() * trans,
                                                in->getDimensions(),
                                                in->getResolution())));
       }
     }
   }
   return moved_states;
 }
コード例 #8
0
 FootstepState::Ptr FootstepGraph::projectFootstep(FootstepState::Ptr in,
                                                   unsigned int& error_state)
 {
   if(!use_pointcloud_model_) {
     return in;
   }
   ros::WallTime start_time = ros::WallTime::now();
   FootstepState::Ptr projected_footstep = in->projectToCloud(
     *tree_model_,
     pointcloud_model_,
     grid_search_,
     *tree_model_2d_,
     pointcloud_model_2d_,
     Eigen::Vector3f(0, 0, 1),
     error_state, parameters_);
   ros::WallTime end_time = ros::WallTime::now();
   perception_duration_ = perception_duration_ + (end_time  - start_time);
   return projected_footstep;
 }
コード例 #9
0
ファイル: footstep_graph.cpp プロジェクト: iory/jsk_control
 FootstepState::Ptr FootstepGraph::projectFootstep(FootstepState::Ptr in,
                                                   unsigned int& error_state)
 {
   ros::WallTime start_time = ros::WallTime::now();
   FootstepState::Ptr projected_footstep = in->projectToCloud(
     *tree_model_,
     pointcloud_model_,
     grid_search_,
     *tree_model_2d_,
     pointcloud_model_2d_,
     Eigen::Vector3f(0, 0, 1),
     error_state,
     plane_estimation_outlier_threshold_,
     plane_estimation_max_iterations_,
     plane_estimation_min_inliers_,
     support_check_x_sampling_,
     support_check_y_sampling_,
     support_check_vertex_neighbor_threshold_);
   ros::WallTime end_time = ros::WallTime::now();
   perception_duration_ = perception_duration_ + (end_time  - start_time);
   return projected_footstep;
 }
コード例 #10
0
  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();
  }
コード例 #11
0
  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));
  }