footstep_planner.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2017, Alexander Stumpf, TU Darmstadt
00003 // Based on http://wiki.ros.org/footstep_planner by Johannes Garimort and Armin Hornung
00004 // All rights reserved.
00005 
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00014 //       group, TU Darmstadt nor the names of its contributors may be used to
00015 //       endorse or promote products derived from this software without
00016 //       specific prior written permission.
00017 
00018 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00022 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00023 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00024 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00025 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00026 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00027 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 //=================================================================================================
00029 
00030 #ifndef FOOTSTEP_PLANNER_H__
00031 #define FOOTSTEP_PLANNER_H__
00032 
00033 #include <ros/ros.h>
00034 #include <tf/tf.h>
00035 
00036 #include <assert.h>
00037 #include <time.h>
00038 
00039 #include <boost/thread.hpp>
00040 #include <boost/thread/mutex.hpp>
00041 #include <boost/function.hpp>
00042 
00043 #include <XmlRpcValue.h>
00044 #include <XmlRpcException.h>
00045 
00046 #include <pcl_conversions/pcl_conversions.h>
00047 
00048 #include <geometry_msgs/Pose.h>
00049 #include <geometry_msgs/PoseStamped.h>
00050 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00051 #include <nav_msgs/Path.h>
00052 #include <nav_msgs/OccupancyGrid.h>
00053 #include <sensor_msgs/PointCloud.h>
00054 #include <sensor_msgs/PointCloud2.h>
00055 #include <visualization_msgs/Marker.h>
00056 #include <visualization_msgs/MarkerArray.h>
00057 
00058 #include <vigir_generic_params/generic_params_msgs.h>
00059 #include <vigir_generic_params/parameter_manager.h>
00060 
00061 #include <vigir_pluginlib/plugin_manager.h>
00062 
00063 #include <vigir_footstep_planning_msgs/footstep_planning_msgs.h>
00064 
00065 #include <vigir_footstep_planning_lib/math.h>
00066 #include <vigir_footstep_planning_lib/modeling/footstep.h>
00067 #include <vigir_footstep_planning_lib/modeling/state.h>
00068 
00069 #include <vigir_footstep_planning_plugins/plugin_aggregators/step_cost_estimator.h>
00070 #include <vigir_footstep_planning_plugins/plugin_aggregators/heuristic.h>
00071 #include <vigir_footstep_planning_plugins/plugin_aggregators/post_processor.h>
00072 #include <vigir_footstep_planning_plugins/plugin_aggregators/robot_model.h>
00073 #include <vigir_footstep_planning_plugins/plugin_aggregators/state_generator.h>
00074 #include <vigir_footstep_planning_plugins/plugin_aggregators/world_model.h>
00075 #include <vigir_footstep_planning_plugins/plugins/step_plan_msg_plugin.h>
00076 
00077 #include <vigir_foot_pose_transformer/foot_pose_transformer.h>
00078 
00079 #include <vigir_footstep_planner/environment_parameters.h>
00080 #include <vigir_footstep_planner/footstep_planner_environment.h>
00081 
00082 
00083 
00084 namespace vigir_footstep_planning
00085 {
00086 typedef std::vector<State>::const_iterator state_iter_t;
00087 
00092 class FootstepPlanner
00093 {
00094 public:
00095   typedef boost::function<void (msgs::StepPlanRequestService::Response)> ResultCB;
00096   typedef boost::function<void (msgs::PlanningFeedback)> FeedbackCB;
00097   typedef boost::function<void ()> PreemptCB;
00098 
00099   FootstepPlanner(ros::NodeHandle &nh);
00100   virtual ~FootstepPlanner();
00101 
00102   bool isPlanning() const;
00103 
00104   bool setParams(const vigir_generic_params::ParameterSet& params);
00105 
00106   msgs::ErrorStatus updateFoot(msgs::Foot& foot, uint8_t mode, bool transform = true) const;
00107   msgs::ErrorStatus updateFeet(msgs::Feet& feet, uint8_t mode, bool transform = true) const;
00108   msgs::ErrorStatus updateStepPlan(msgs::StepPlan& result, uint8_t mode, const std::string& param_set_name = std::string(), bool transform = true) const;
00109 
00110   msgs::ErrorStatus stepPlanRequest(msgs::StepPlanRequestService::Request& req, ResultCB result_cb = ResultCB(), FeedbackCB feedback_cb = FeedbackCB(), PreemptCB preempt_cb = PreemptCB());
00112   bool stepPlanRequestService(msgs::StepPlanRequestService::Request& req, msgs::StepPlanRequestService::Response& resp);
00113 
00115   void preemptPlanning();
00116 
00117   // typedefs
00118   typedef boost::shared_ptr<FootstepPlanner> Ptr;
00119   typedef boost::shared_ptr<const FootstepPlanner> ConstPtr;
00120 
00121 protected:
00129   msgs::ErrorStatus planSteps(msgs::StepPlanRequestService::Request& req);
00130 
00132   msgs::ErrorStatus planPattern(msgs::StepPlanRequestService::Request& req);
00133   msgs::ErrorStatus finalizeAndAddStepToPlan(State& s, const msgs::PatternParameters& env_params, bool change_z = true);
00134 
00136   bool finalizeStepPlan(msgs::StepPlanRequestService::Request& req, msgs::StepPlanRequestService::Response& resp, bool post_process);
00137 
00139   void startPlanning(msgs::StepPlanRequestService::Request& req);
00141   void doPlanning(msgs::StepPlanRequestService::Request& req);
00142 
00143   bool findNearestValidState(State& s) const;
00144 
00145   bool checkRobotCollision(const State& left_foot, const State& right_foot, bool& left, bool& right) const;
00146 
00152   bool setStart(const State& left_foot, const State& right_foot, bool ignore_collision = false);
00153 
00159   bool setStart(const msgs::StepPlanRequest& req, bool ignore_collision = false);
00160 
00166   bool setGoal(const State& left_foot, const State& right_foot, bool ignore_collision = false);
00167 
00173   bool setGoal(const msgs::StepPlanRequest& req, bool ignore_collision = false);
00174 
00176   double getPathCosts() const { return ivPathCost; }
00177 
00179   size_t getNumExpandedStates() const
00180   {
00181     return ivPlannerPtr->get_n_expands();
00182   }
00183 
00185   size_t getNumFootPoses() const { return ivPath.size(); }
00186 
00187   state_iter_t getPathBegin() const { return ivPath.begin(); }
00188   state_iter_t getPathEnd() const { return ivPath.end(); }
00189 
00191   int getPathSize() { return ivPath.size(); }
00192 
00193   State getStartFootLeft() { return ivStartFootLeft; }
00194   State getStartFootRight() { return ivStartFootRight; }
00195 
00197   void reset();
00198 
00200   void resetTotally();
00201 
00203   bool pathExists() { return (bool)ivPath.size(); }
00204 
00209   bool pathIsNew(const std::vector<int>& new_path);
00210 
00215   bool extractPath(const std::vector<int>& state_ids);
00216 
00223   bool plan(ReplanParams& params);
00224 
00226   State getFootPose(const State& robot, Leg leg, double dx, double dy, double dyaw);
00227   State getFootPose(const State& robot, Leg leg);
00228 
00230   void setPlanner();
00231 
00232   // publisher
00233   ros::Publisher ivCheckedFootContactSupportPub;
00234 
00235   mutable boost::recursive_mutex planner_mutex;
00236   boost::thread planning_thread;
00237 
00238   ResultCB result_cb;
00239   FeedbackCB feedback_cb;
00240   PreemptCB preempt_cb;
00241 
00242   boost::shared_ptr<FootstepPlannerEnvironment> ivPlannerEnvironmentPtr;
00243   boost::shared_ptr<SBPLPlanner> ivPlannerPtr;
00244 
00245   std::vector<State> ivPath;
00246 
00247   State ivStartFootLeft;
00248   State ivStartFootRight;
00249   State ivGoalFootLeft;
00250   State ivGoalFootRight;
00251 
00252   // local instance of foot pose transformer
00253   FootPoseTransformer foot_pose_transformer;
00254 
00255   // Parameters
00256   std::string frame_id;
00257   EnvironmentParameters::Ptr env_params;
00258   unsigned int start_foot_selection;
00259   bool start_pose_set_up, goal_pose_set_up;
00260 
00261   double max_number_steps;
00262 
00263   // robot parameters
00264   double max_path_length_ratio;
00265 
00266   double ivPathCost;
00267 
00268   std::vector<int> ivPlanningStatesIds;
00269 
00270   pcl::PointCloud<pcl::PointXYZI>::Ptr ivCheckedFootContactSupport;
00271 
00272   // counter to be used as sequence number
00273   unsigned int step_plan_uid;
00274 };
00275 }
00276 
00277 #endif


vigir_footstep_planner
Author(s): Alexander Stumpf
autogenerated on Fri Apr 7 2017 02:59:36