3 #ifndef JSK_FOOTSTEP_PLANNER_GRID_PATH_PLANNER_H_ 
    4 #define JSK_FOOTSTEP_PLANNER_GRID_PATH_PLANNER_H_ 
   10 #include <sensor_msgs/PointCloud2.h> 
   12 #include <jsk_rviz_plugins/OverlayText.h> 
   13 #include <jsk_footstep_msgs/FootstepArray.h> 
   14 #include <jsk_footstep_msgs/PlanFootstepsAction.h> 
   16 #include <jsk_footstep_planner/CollisionBoundingBoxInfo.h> 
   19 #include <pcl/kdtree/kdtree_flann.h> 
   48     virtual void obstacleCallback(
const sensor_msgs::PointCloud2::ConstPtr& msg);
 
   49     virtual void planCB(
const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr& goal);
 
   52       jsk_footstep_planner::CollisionBoundingBoxInfo::Request& req,
 
   53       jsk_footstep_planner::CollisionBoundingBoxInfo::Response& res);
 
   61       const pcl::PointCloud<pcl::PointXYZRGB>& 
cloud,
 
   63       const std_msgs::Header& header);
 
   66                              const std::string& text,
 
   75     inline virtual void gridToPoint(
const int ix, 
const int iy, Eigen::Vector3f &
p)
 
   81     inline virtual void pointToGrid(
const Eigen::Vector3f &
p, 
int &ix, 
int &iy)
 
   92       int ix = node->getState()->indexX();
 
   93       int iy = node->getState()->indexY();
 
   94       double gx = 
graph->getGoalState()->indexX() - ix;
 
   95       double gy = 
graph->getGoalState()->indexY() - iy;
 
   97       return std::sqrt(gx * gx + gy * gy);
 
  102     jsk_footstep_msgs::PlanFootstepsResult 
result_;