37 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_GRAPH_H_ 
   38 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_GRAPH_H_ 
   42 #include <jsk_footstep_msgs/FootstepArray.h> 
   54   class FootstepGraph: 
public Graph<FootstepState>
 
   64                   const bool use_pointcloud_model = 
false,
 
   65                   const bool lazy_projection = 
true,
 
   66                   const bool local_movement = 
false,
 
   67                   const bool use_obstacle_model = 
false):
 
   89       std::vector<StatePtr> ret;
 
  107     virtual bool isCollidingBox(
const Eigen::Affine3f& c, pcl::PointIndices::Ptr candidates) 
const;
 
  115       std::vector<Eigen::Affine3f> left_to_right_successors);
 
  145       if (leg == jsk_footstep_msgs::Footstep::LEFT) {
 
  148       else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
 
  176       pcl::ProjectInliers<pcl::PointNormal> proj;
 
  177       proj.setModelType(pcl::SACMODEL_PLANE);
 
  178       pcl::ModelCoefficients::Ptr
 
  179         plane_coefficients (
new pcl::ModelCoefficients);
 
  180       plane_coefficients->values.resize(4.0);
 
  181       plane_coefficients->values[2] = 1.0; 
 
  182       proj.setModelCoefficients(plane_coefficients);
 
  225       return prev_cost + 1;
 
  284     double first_rotation_weight,
 
  285     double second_rotation_weight);