navfn_ros.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
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/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage 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 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #ifndef NAVFN_NAVFN_ROS_H_
00038 #define NAVFN_NAVFN_ROS_H_
00039 
00040 #include <ros/ros.h>
00041 #include <navfn/navfn.h>
00042 #include <costmap_2d/costmap_2d.h>
00043 #include <geometry_msgs/PoseStamped.h>
00044 #include <geometry_msgs/Point.h>
00045 #include <nav_msgs/Path.h>
00046 #include <tf/transform_datatypes.h>
00047 #include <vector>
00048 #include <nav_core/base_global_planner.h>
00049 #include <nav_msgs/GetPlan.h>
00050 #include <navfn/potarr_point.h>
00051 #include <pcl_ros/publisher.h>
00052 
00053 namespace navfn {
00058   class NavfnROS : public nav_core::BaseGlobalPlanner {
00059     public:
00063       NavfnROS();
00064 
00070       NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00071 
00078       NavfnROS(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame);
00079 
00085       void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00086 
00093       void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame);
00094 
00102       bool makePlan(const geometry_msgs::PoseStamped& start, 
00103           const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00104 
00113       bool makePlan(const geometry_msgs::PoseStamped& start, 
00114           const geometry_msgs::PoseStamped& goal, double tolerance, std::vector<geometry_msgs::PoseStamped>& plan);
00115 
00121       bool computePotential(const geometry_msgs::Point& world_point);
00122 
00129       bool getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00130 
00136       double getPointPotential(const geometry_msgs::Point& world_point);
00137 
00143       bool validPointPotential(const geometry_msgs::Point& world_point);
00144 
00151       bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
00152 
00156       void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, double r, double g, double b, double a);
00157 
00158       ~NavfnROS(){}
00159 
00160       bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
00161 
00162     protected:
00163 
00167       costmap_2d::Costmap2D* costmap_;
00168       boost::shared_ptr<NavFn> planner_;
00169       ros::Publisher plan_pub_;
00170       pcl_ros::Publisher<PotarrPoint> potarr_pub_;
00171       bool initialized_, allow_unknown_, visualize_potential_;
00172 
00173 
00174     private:
00175       inline double sq_distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){
00176         double dx = p1.pose.position.x - p2.pose.position.x;
00177         double dy = p1.pose.position.y - p2.pose.position.y;
00178         return dx*dx +dy*dy;
00179       }
00180 
00181       void mapToWorld(double mx, double my, double& wx, double& wy);
00182       void clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my);
00183       double planner_window_x_, planner_window_y_, default_tolerance_;
00184       std::string tf_prefix_;
00185       boost::mutex mutex_;
00186       ros::ServiceServer make_plan_srv_;
00187       std::string global_frame_;
00188   };
00189 };
00190 
00191 #endif


explore
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:06