39 #include <jsk_recognition_msgs/PolygonArray.h> 
   40 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 
   41 #include <jsk_interactive_marker/FootstepMarkerConfig.h> 
   44 #include <jsk_interactive_marker/SetPose.h> 
   45 #include <jsk_interactive_marker/MarkerSetPose.h> 
   48 #include <geometry_msgs/PointStamped.h> 
   55 #include <jsk_footstep_msgs/PlanFootstepsAction.h> 
   56 #include <jsk_footstep_msgs/ExecFootstepsAction.h> 
   57 #include <geometry_msgs/Polygon.h> 
   58 #include <std_msgs/UInt8.h> 
   59 #include <std_msgs/Empty.h> 
   60 #include <std_srvs/Empty.h> 
   61 #include <jsk_recognition_msgs/SimpleOccupancyGridArray.h> 
   62 #include <dynamic_reconfigure/server.h> 
   66   typedef jsk_interactive_marker::FootstepMarkerConfig 
Config;
 
   74   typedef jsk_footstep_msgs::PlanFootstepsResult 
PlanResult;
 
   77   void processFeedbackCB(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
 
   78   void menuFeedbackCB(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
 
   82   void resumeCB(
const std_msgs::Empty::ConstPtr& 
msg);
 
   84                   const PlanResult::ConstPtr &
result);
 
   97   bool forceToReplan(std_srvs::Empty::Request& req, std_srvs::Empty::Request& res);
 
  100   std::shared_ptr<dynamic_reconfigure::Server<Config> > 
srv_;
 
  104   jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr 
latest_grids_;
 
  121   std::shared_ptr<interactive_markers::InteractiveMarkerServer> 
server_;