29 #ifndef FOOTSTEP_PLANNER_NODE_H__ 30 #define FOOTSTEP_PLANNER_NODE_H__ 34 #include <boost/thread/mutex.hpp> 35 #include <boost/bind.hpp> 37 #include <geometry_msgs/PoseStamped.h> 38 #include <geometry_msgs/PoseWithCovarianceStamped.h> 40 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h> 41 #include <vigir_footstep_planning_msgs/visualization.h> 65 void planningResultActionCallback(
const msgs::StepPlanRequestService::Response& resp, SimpleActionServer<msgs::StepPlanRequestAction>::Ptr& as);
73 void setParams(
const std_msgs::StringConstPtr& params_name);
74 void stepPlanRequest(
const msgs::StepPlanRequestConstPtr& plan_request);
78 bool stepPlanRequestService(msgs::StepPlanRequestService::Request& req, msgs::StepPlanRequestService::Response& resp);
79 bool updateFootService(msgs::UpdateFootService::Request& req, msgs::UpdateFootService::Response& resp);
80 bool updateFeetService(msgs::UpdateFeetService::Request& req, msgs::UpdateFeetService::Response& resp);
81 bool updateStepPlanService(msgs::UpdateStepPlanService::Request& req, msgs::UpdateStepPlanService::Response& resp);