Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_
00026 #define FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_
00027
00028 #include <geometry_msgs/Pose.h>
00029 #include <geometry_msgs/PoseStamped.h>
00030 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00031 #include <humanoid_nav_msgs/PlanFootsteps.h>
00032 #include <footstep_planner/helper.h>
00033 #include <footstep_planner/PathCostHeuristic.h>
00034 #include <footstep_planner/FootstepPlannerEnvironment.h>
00035 #include <footstep_planner/PlanningStateChangeQuery.h>
00036 #include <footstep_planner/State.h>
00037 #include <nav_msgs/Path.h>
00038 #include <nav_msgs/OccupancyGrid.h>
00039 #include <ros/ros.h>
00040 #include <sensor_msgs/PointCloud.h>
00041 #include <tf/tf.h>
00042 #include <visualization_msgs/Marker.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <XmlRpcValue.h>
00045 #include <XmlRpcException.h>
00046
00047 #include <assert.h>
00048 #include <time.h>
00049
00050
00051 namespace footstep_planner
00052 {
00053 typedef std::vector<State>::const_iterator state_iter_t;
00054
00059 class FootstepPlanner
00060 {
00061 public:
00062 FootstepPlanner();
00063 virtual ~FootstepPlanner();
00064
00072 bool plan();
00073
00075 bool plan(const geometry_msgs::PoseStampedConstPtr start,
00076 const geometry_msgs::PoseStampedConstPtr goal);
00077
00079 bool plan(float start_x, float start_y, float start_theta,
00080 float goal_x, float goal_y, float goal_theta);
00081
00089 bool replan();
00090
00092 bool planService(humanoid_nav_msgs::PlanFootsteps::Request &req,
00093 humanoid_nav_msgs::PlanFootsteps::Response &resp);
00094
00100 bool setGoal(const geometry_msgs::PoseStampedConstPtr goal_pose);
00101
00107 bool setGoal(float x, float y, float theta);
00108
00114 bool setStart(const geometry_msgs::PoseStampedConstPtr start_pose);
00115
00121 bool setStart(float x, float y, float theta);
00122
00128 bool setStart(const State& left_foot, const State& right_foot);
00129
00136 bool updateMap(const gridmap_2d::GridMap2DPtr map);
00137
00138 void setMarkerNamespace(const std::string& ns)
00139 {
00140 ivMarkerNamespace = ns;
00141 };
00142
00144 void setMaxSearchTime(int search_time)
00145 {
00146 ivMaxSearchTime = search_time;
00147 };
00148
00158 void goalPoseCallback(
00159 const geometry_msgs::PoseStampedConstPtr& goal_pose);
00169 void startPoseCallback(
00170 const geometry_msgs::PoseWithCovarianceStampedConstPtr& start_pose);
00171
00177 void mapCallback(const nav_msgs::OccupancyGridConstPtr& occupancy_map);
00178
00183 void clearFootstepPathVis(unsigned num_footsteps=0);
00184
00186 double getPathCosts() const { return ivPathCost; };
00187
00189 size_t getNumExpandedStates() const
00190 {
00191 return ivPlannerPtr->get_n_expands();
00192 };
00193
00195 size_t getNumFootPoses() const { return ivPath.size(); };
00196
00197 state_iter_t getPathBegin() const { return ivPath.begin(); };
00198 state_iter_t getPathEnd() const { return ivPath.end(); };
00199
00201 int getPathSize() { return ivPath.size(); };
00202
00203 State getStartFootLeft() { return ivStartFootLeft; };
00204 State getStartFootRight() { return ivStartFootRight; };
00205
00207 void reset();
00208
00210 void resetTotally();
00211
00213 bool pathExists() { return (bool)ivPath.size(); };
00214
00216 environment_params ivEnvironmentParams;
00217
00218 protected:
00219 void broadcastExpandedNodesVis();
00220 void broadcastRandomNodesVis();
00221 void broadcastFootstepPathVis();
00222 void broadcastHeuristicPathVis();
00223 void broadcastPathVis();
00224
00229 bool pathIsNew(const std::vector<int>& new_path);
00230
00235 bool extractPath(const std::vector<int>& state_ids);
00236
00238 void footPoseToMarker(const State& footstep,
00239 visualization_msgs::Marker* marker);
00240
00247 bool run();
00248
00250 State getFootPose(const State& robot, Leg side);
00251
00253 void setPlanner();
00254
00256 void updateEnvironment(const gridmap_2d::GridMap2DPtr old_map);
00257
00258 boost::shared_ptr<FootstepPlannerEnvironment> ivPlannerEnvironmentPtr;
00259 gridmap_2d::GridMap2DPtr ivMapPtr;
00260 boost::shared_ptr<SBPLPlanner> ivPlannerPtr;
00261
00262 boost::shared_ptr<const PathCostHeuristic> ivPathCostHeuristicPtr;
00263
00264 std::vector<State> ivPath;
00265
00266 State ivStartFootLeft;
00267 State ivStartFootRight;
00268 State ivGoalFootLeft;
00269 State ivGoalFootRight;
00270
00271 ros::Publisher ivExpandedStatesVisPub;
00272 ros::Publisher ivFootstepPathVisPub;
00273 ros::Publisher ivRandomStatesVisPub;
00274 ros::Subscriber ivGridMapSub;
00275 ros::Publisher ivHeuristicPathVisPub;
00276 ros::Publisher ivPathVisPub;
00277 ros::Publisher ivStartPoseVisPub;
00278 ros::ServiceServer ivFootstepPlanService;
00279
00280 double ivFootSeparation;
00281 double ivMaxStepWidth;
00282 int ivCollisionCheckAccuracy;
00283
00284 bool ivStartPoseSetUp, ivGoalPoseSetUp;
00285 int ivLastMarkerMsgSize;
00286 double ivPathCost;
00287 bool ivSearchUntilFirstSolution;
00288 double ivMaxSearchTime;
00289 double ivInitialEpsilon;
00290
00295 int ivChangedCellsLimit;
00296
00297 std::string ivPlannerType;
00298 std::string ivMarkerNamespace;
00299
00300 std::vector<int> ivPlanningStatesIds;
00301 };
00302 }
00303
00304 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_