22 #ifndef FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_ 23 #define FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_ 25 #include <geometry_msgs/Pose.h> 26 #include <geometry_msgs/PoseStamped.h> 27 #include <geometry_msgs/PoseWithCovarianceStamped.h> 28 #include <humanoid_nav_msgs/PlanFootsteps.h> 29 #include <humanoid_nav_msgs/PlanFootstepsBetweenFeet.h> 35 #include <nav_msgs/Path.h> 36 #include <nav_msgs/OccupancyGrid.h> 38 #include <sensor_msgs/PointCloud.h> 40 #include <visualization_msgs/Marker.h> 41 #include <visualization_msgs/MarkerArray.h> 70 bool plan(
bool force_new_plan=
true);
73 bool plan(
const geometry_msgs::PoseStampedConstPtr
start,
74 const geometry_msgs::PoseStampedConstPtr
goal);
77 bool plan(
float start_x,
float start_y,
float start_theta,
78 float goal_x,
float goal_y,
float goal_theta);
90 bool planService(humanoid_nav_msgs::PlanFootsteps::Request &req,
91 humanoid_nav_msgs::PlanFootsteps::Response &
resp);
94 bool planFeetService(humanoid_nav_msgs::PlanFootstepsBetweenFeet::Request &req,
95 humanoid_nav_msgs::PlanFootstepsBetweenFeet::Response &resp);
109 bool setGoal(
const geometry_msgs::PoseStampedConstPtr goal_pose);
123 bool setStart(
const geometry_msgs::PoseStampedConstPtr start_pose);
130 bool setStart(
float x,
float y,
float theta);
168 const geometry_msgs::PoseStampedConstPtr& goal_pose);
179 const geometry_msgs::PoseWithCovarianceStampedConstPtr& start_pose);
186 void mapCallback(
const nav_msgs::OccupancyGridConstPtr& occupancy_map);
241 bool pathIsNew(
const std::vector<int>& new_path);
247 bool extractPath(
const std::vector<int>& state_ids);
251 visualization_msgs::Marker* marker);
317 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_