footstep_planner.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_
00038 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_PLANNER_H_
00039 
00040 #include <ros/ros.h>
00041 #include <actionlib/server/simple_action_server.h>
00042 
00043 // ros
00044 #include <jsk_footstep_msgs/FootstepArray.h>
00045 #include <jsk_footstep_msgs/PlanFootstepsAction.h>
00046 #include <jsk_footstep_planner/FootstepPlannerConfig.h>
00047 #include <sensor_msgs/PointCloud2.h>
00048 #include <dynamic_reconfigure/server.h>
00049 #include <jsk_rviz_plugins/OverlayText.h>
00050 
00051 // footstep planning
00052 #include "jsk_footstep_planner/footstep_graph.h"
00053 #include "jsk_footstep_planner/astar_solver.h"
00054 #include "jsk_footstep_planner/footstep_astar_solver.h"
00055 
00056 #include <jsk_interactive_marker/SnapFootPrint.h>
00057 
00058 namespace jsk_footstep_planner
00059 {
00060 
00061   enum PlanningStatus
00062   {
00063     OK, WARNING, ERROR
00064   };
00069   class FootstepPlanner
00070   {
00071   public:
00072     typedef boost::shared_ptr<FootstepPlanner> Ptr;
00073     typedef FootstepPlannerConfig Config;
00074     FootstepPlanner(ros::NodeHandle& nh);
00075   protected:
00076 
00077     // Initialization
00078     virtual bool readSuccessors(ros::NodeHandle& nh);
00079     
00080     virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
00081     virtual void planCB(const jsk_footstep_msgs::PlanFootstepsGoal::ConstPtr& goal);
00082 
00083     // buildGraph is not thread safe, it is responsible for caller to take care
00084     // of mutex
00085     virtual void buildGraph();
00086 
00087     virtual void configCallback(Config &config, uint32_t level);
00088 
00089     virtual double stepCostHeuristic(
00090       SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph);
00091     virtual double zeroHeuristic(
00092       SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph);
00093     virtual double straightHeuristic(
00094       SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph);
00095     virtual double straightRotationHeuristic(
00096       SolverNode<FootstepState, FootstepGraph>::Ptr node, FootstepGraph::Ptr graph);
00097     virtual void profile(FootstepAStarSolver<FootstepGraph>& solver, FootstepGraph::Ptr graph);
00098     virtual void publishPointCloud(
00099       const pcl::PointCloud<pcl::PointNormal>& cloud,
00100       ros::Publisher& pub,
00101       const std_msgs::Header& header);
00102     virtual bool projectFootPrint(
00103       const Eigen::Affine3f& center_pose,
00104       const Eigen::Affine3f& left_pose_trans,
00105       const Eigen::Affine3f& right_pose_trans,
00106       geometry_msgs::Pose& pose);
00107 
00108     virtual bool projectFootPrintService(
00109       jsk_interactive_marker::SnapFootPrint::Request& req,
00110       jsk_interactive_marker::SnapFootPrint::Response& res);
00111     virtual bool projectFootPrintWithLocalSearchService(
00112       jsk_interactive_marker::SnapFootPrint::Request& req,
00113       jsk_interactive_marker::SnapFootPrint::Response& res);
00114     virtual void publishText(ros::Publisher& pub,
00115                              const std::string& text,
00116                              PlanningStatus status);
00117     boost::mutex mutex_;
00118     actionlib::SimpleActionServer<jsk_footstep_msgs::PlanFootstepsAction> as_;
00119     jsk_footstep_msgs::PlanFootstepsResult result_;
00120     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00121     ros::Publisher pub_close_list_;
00122     ros::Publisher pub_open_list_;
00123     ros::Publisher pub_text_;
00124     ros::Subscriber sub_pointcloud_model_;
00125     ros::ServiceServer srv_project_footprint_;
00126     ros::ServiceServer srv_project_footprint_with_local_search_;
00127     pcl::PointCloud<pcl::PointNormal>::Ptr pointcloud_model_;
00128     FootstepGraph::Ptr graph_;
00129     std::vector<Eigen::Affine3f> successors_;
00130     std_msgs::Header latest_header_;
00131     // Parameters
00132     bool rich_profiling_;
00133     bool use_pointcloud_model_;
00134     bool use_lazy_perception_;
00135     bool use_local_movement_;
00136     bool use_transition_limit_;
00137     bool project_start_state_;
00138     bool project_goal_state_;
00139     double local_move_x_;
00140     double local_move_y_;
00141     double local_move_theta_;
00142     int local_move_x_num_;
00143     int local_move_y_num_;
00144     int local_move_theta_num_;
00145     double transition_limit_x_;
00146     double transition_limit_y_;
00147     double transition_limit_z_;
00148     double transition_limit_roll_;
00149     double transition_limit_pitch_;
00150     double transition_limit_yaw_;
00151     double goal_pos_thr_;
00152     double goal_rot_thr_;
00153     int plane_estimation_max_iterations_;
00154     int plane_estimation_min_inliers_;
00155     double plane_estimation_outlier_threshold_;
00156     int support_check_x_sampling_;
00157     int support_check_y_sampling_;
00158     double support_check_vertex_neighbor_threshold_;
00159     double resolution_x_;
00160     double resolution_y_;
00161     double resolution_theta_;
00162     double footstep_size_x_;
00163     double footstep_size_y_;
00164     int close_list_x_num_;
00165     int close_list_y_num_;
00166     int close_list_theta_num_;
00167     int profile_period_;
00168     std::string heuristic_;
00169     double heuristic_first_rotation_weight_;
00170     double heuristic_second_rotation_weight_;
00171     double cost_weight_;
00172     double heuristic_weight_;
00173   private:
00174     
00175   };
00176 }
00177 
00178 #endif


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:56