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 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef SBPL_CART_PLANNER_H
00039 #define SBPL_CART_PLANNER_H
00040 
00041 #include <iostream>
00042 #include <vector>
00043 
00044 using namespace std;
00045 
00047 #include <ros/ros.h>
00048 
00049 
00050 #include <costmap_2d/costmap_2d_ros.h>
00051 
00052 
00053 #include <sbpl/headers.h>
00054 
00055 
00056 #include <nav_core/base_global_planner.h>
00057 
00058 #include <sbpl_cart_planner/environment_cart_planner.h>
00059 #include <visualization_msgs/MarkerArray.h>
00060 
00061 class SBPLCartPlanner : public nav_core::BaseGlobalPlanner{
00062 public:
00063   
00067   SBPLCartPlanner();
00068 
00069   
00075   SBPLCartPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00076 
00077 
00083   virtual void initialize(std::string name, 
00084                           costmap_2d::Costmap2DROS* costmap_ros);
00085   
00093   virtual bool makePlan(const geometry_msgs::PoseStamped& start, 
00094                         const geometry_msgs::PoseStamped& goal, 
00095                         std::vector<geometry_msgs::PoseStamped>& plan);
00096 
00097   virtual ~SBPLCartPlanner(){};
00098 
00099 private:
00100   bool initialized_;
00101 
00102   SBPLPlanner* planner_;
00103   EnvironmentNAVXYTHETACARTLAT* env_;
00104   
00105   std::string planner_type_; 
00107   double allocated_time_; 
00108   double initial_epsilon_; 
00110   std::string environment_type_; 
00111   std::string cost_map_topic_; 
00113   bool forward_search_; 
00114   std::string primitive_filename_; 
00115   int force_scratch_limit_; 
00118   costmap_2d::Costmap2DROS* costmap_ros_; 
00119   costmap_2d::Costmap2D cost_map_;        
00121   ros::Publisher plan_pub_,sbpl_plan_pub_,sbpl_plan_footprint_pub_,sbpl_robot_cart_plan_pub_, stats_publisher_;
00122   
00123   std::vector<geometry_msgs::Point> footprint_;
00124   std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node);
00125 
00126   double sign(double x);
00127   sbpl_2Dpt_t cart_offset_, cart_cp_offset_;
00128 
00129   void convertPathToMarkerArray(const std::vector<EnvNAVXYTHETACARTLAT3Dpt_t> &sbpl_path,
00130                                 const std::string &path_frame_id,
00131                                 visualization_msgs::MarkerArray &ma);
00132 
00133   std::vector<geometry_msgs::Point> cart_footprint_,robot_footprint_;
00134 
00135   void transformFootprintToEdges(const geometry_msgs::Pose &robot_pose,
00136                                  const std::vector<geometry_msgs::Point> &footprint,
00137                                  std::vector<geometry_msgs::Point> &out_footprint);
00138 
00139   void getFootprintList(const std::vector<EnvNAVXYTHETACARTLAT3Dpt_t> &sbpl_path,
00140                         const std::string &path_frame_id,
00141                         visualization_msgs::MarkerArray &ma);
00142   geometry_msgs::Pose getGlobalCartPose(const EnvNAVXYTHETACARTLAT3Dpt_t& sbpl_pose);
00143   geometry_msgs::Pose getLocalCartPose(const EnvNAVXYTHETACARTLAT3Dpt_t& sbpl_pose);
00144   geometry_msgs::Pose getLocalCartControlFramePose(const EnvNAVXYTHETACARTLAT3Dpt_t& sbpl_pose);
00145 
00146   bool clearFootprint(const geometry_msgs::Pose &robot_pose, 
00147                       const std::vector<geometry_msgs::Point> &footprint);
00148   
00149   void getOrientedFootprint(const geometry_msgs::Pose &robot_pose,
00150                             const std::vector<geometry_msgs::Point> &footprint,
00151                             std::vector<geometry_msgs::Point> &oriented_footprint);
00152 
00153   geometry_msgs::Pose getGlobalCartPose(const geometry_msgs::Pose &robot_pose, const double &cart_angle);
00154 
00155   unsigned char costMapCostToSBPLCost(unsigned char newcost);
00156 
00157   unsigned char sbpl_cost_multiplier_;
00158   unsigned char lethal_obstacle_;
00159   unsigned char inscribed_inflated_obstacle_;
00160   unsigned int num_sbpl_markers_;
00161   int visualizer_skip_poses_;
00162 };
00163 
00164 #endif
00165