$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/footstep_planner/include/footstep_planner/FootstepPlanner.h $ 00002 // SVN $Id: FootstepPlanner.h 3979 2013-02-26 14:13:46Z garimort@informatik.uni-freiburg.de $ 00003 00004 /* 00005 * A footstep planner for humanoid robots. 00006 * 00007 * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg 00008 * http://www.ros.org/wiki/footstep_planner 00009 * 00010 * 00011 * This program is free software: you can redistribute it and/or modify 00012 * it under the terms of the GNU General Public License as published by 00013 * the Free Software Foundation, version 3. 00014 * 00015 * This program is distributed in the hope that it will be useful, 00016 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00017 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00018 * GNU General Public License for more details. 00019 * 00020 * You should have received a copy of the GNU General Public License 00021 * along with this program. If not, see <http://www.gnu.org/licenses/>. 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 00049 00050 namespace footstep_planner 00051 { 00052 typedef std::vector<State>::const_iterator state_iter_t; 00053 00058 class FootstepPlanner 00059 { 00060 public: 00061 FootstepPlanner(); 00062 virtual ~FootstepPlanner(); 00063 00071 bool plan(); 00072 00074 bool plan(const geometry_msgs::PoseStampedConstPtr& start, 00075 const geometry_msgs::PoseStampedConstPtr& goal); 00076 00078 bool plan(float start_x, float start_y, float start_theta, 00079 float goal_x, float goal_y, float goal_theta); 00080 00088 bool replan(); 00089 00091 bool planService(humanoid_nav_msgs::PlanFootsteps::Request &req, 00092 humanoid_nav_msgs::PlanFootsteps::Response &resp); 00093 00099 bool setGoal(const geometry_msgs::PoseStampedConstPtr& goal_pose); 00100 00106 bool setGoal(float x, float y, float theta); 00107 00113 bool setStart(const geometry_msgs::PoseStampedConstPtr& start_pose); 00114 00120 bool setStart(float x, float y, float theta); 00121 00127 bool setStart(const State& left_foot, const State& right_foot); 00128 00135 bool updateMap(const gridmap_2d::GridMap2DPtr& map); 00136 00137 void setMarkerNamespace(const std::string& ns) 00138 { 00139 ivMarkerNamespace = ns; 00140 }; 00141 00143 void setMaxSearchTime(int search_time) 00144 { 00145 ivMaxSearchTime = search_time; 00146 }; 00147 00157 void goalPoseCallback( 00158 const geometry_msgs::PoseStampedConstPtr& goal_pose); 00168 void startPoseCallback( 00169 const geometry_msgs::PoseWithCovarianceStampedConstPtr& start_pose); 00170 00176 void mapCallback(const nav_msgs::OccupancyGridConstPtr& occupancy_map); 00177 00182 void clearFootstepPathVis(unsigned num_footsteps=0); 00183 00185 double getPathCosts() const { return ivPathCost; }; 00186 00188 size_t getNumExpandedStates() const 00189 { 00190 return ivPlannerPtr->get_n_expands(); 00191 }; 00192 00194 size_t getNumFootPoses() const { return ivPath.size(); }; 00195 00196 state_iter_t getPathBegin() const { return ivPath.begin(); }; 00197 state_iter_t getPathEnd() const { return ivPath.end(); }; 00198 00200 int getPathSize() { return ivPath.size(); }; 00201 00202 State getStartFootLeft() { return ivStartFootLeft; }; 00203 State getStartFootRight() { return ivStartFootRight; }; 00204 00206 void reset(); 00207 00209 void resetTotally(); 00210 00212 bool pathExists() { return ivPathExists; }; 00213 00214 protected: 00215 void broadcastExpandedNodesVis(); 00216 void broadcastRandomNodesVis(); 00217 void broadcastFootstepPathVis(); 00218 void broadcastHeuristicPathVis(); 00219 void broadcastPathVis(); 00220 00225 bool pathIsNew(const std::vector<int>& new_path); 00226 00231 bool extractPath(const std::vector<int>& state_ids); 00232 00234 void footPoseToMarker(const State& footstep, 00235 visualization_msgs::Marker* marker); 00236 00243 bool run(); 00244 00246 State getFootPose(const State& robot, Leg side); 00247 00249 void setPlanner(); 00250 00252 void updateEnvironment(const gridmap_2d::GridMap2DPtr& old_map); 00253 00254 boost::shared_ptr<FootstepPlannerEnvironment> ivPlannerEnvironmentPtr; 00255 gridmap_2d::GridMap2DPtr ivMapPtr; 00256 boost::shared_ptr<SBPLPlanner> ivPlannerPtr; 00257 00258 boost::shared_ptr<const PathCostHeuristic> ivPathCostHeuristicPtr; 00259 00260 std::vector<State> ivPath; 00261 00262 State ivStartFootLeft; 00263 State ivStartFootRight; 00264 State ivGoalFootLeft; 00265 State ivGoalFootRight; 00266 00267 ros::Publisher ivExpandedStatesVisPub; 00268 ros::Publisher ivFootstepPathVisPub; 00269 ros::Publisher ivRandomStatesVisPub; 00270 ros::Subscriber ivGridMapSub; 00271 ros::Publisher ivHeuristicPathVisPub; 00272 ros::Publisher ivPathVisPub; 00273 ros::Publisher ivStartPoseVisPub; 00274 ros::ServiceServer ivFootstepPlanService; 00275 00276 double ivFootSeparation; 00277 double ivMaxStepWidth; 00278 int ivCollisionCheckAccuracy; 00279 00280 bool ivStartPoseSetUp, ivGoalPoseSetUp; 00281 bool ivPathExists; 00282 int ivLastMarkerMsgSize; 00283 double ivPathCost; 00284 bool ivSearchUntilFirstSolution; 00285 double ivMaxSearchTime; 00286 double ivInitialEpsilon; 00287 00292 int ivChangedCellsLimit; 00293 00294 std::string ivPlannerType; 00295 std::string ivMarkerNamespace; 00296 00297 std::vector<int> ivPlanningStatesIds; 00298 00299 environment_params ivEnvironmentParams; 00300 }; 00301 } 00302 00303 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNER_H_