planner_core.h
Go to the documentation of this file.
1 #ifndef _PLANNERCORE_H
2 #define _PLANNERCORE_H
3 /*********************************************************************
4  *
5  * Software License Agreement (BSD License)
6  *
7  * Copyright (c) 2008, 2013, Willow Garage, Inc.
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of Willow Garage, Inc. nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * Author: Eitan Marder-Eppstein
38  * David V. Lu!!
39  *********************************************************************/
40 #define POT_HIGH 1.0e10 // unassigned cell potential
41 #include <ros/ros.h>
42 #include <costmap_2d/costmap_2d.h>
43 #include <geometry_msgs/PoseStamped.h>
44 #include <geometry_msgs/Point.h>
45 #include <nav_msgs/Path.h>
46 #include <tf/transform_datatypes.h>
47 #include <vector>
49 #include <nav_msgs/GetPlan.h>
50 #include <dynamic_reconfigure/server.h>
55 #include <global_planner/GlobalPlannerConfig.h>
56 
57 namespace global_planner {
58 
59 class Expander;
60 class GridPath;
61 
68  public:
72  GlobalPlanner();
73 
80  GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
81 
86 
92  void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
93 
94  void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
95 
103  bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
104  std::vector<geometry_msgs::PoseStamped>& plan);
105 
114  bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance,
115  std::vector<geometry_msgs::PoseStamped>& plan);
116 
122  bool computePotential(const geometry_msgs::Point& world_point);
123 
134  bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y,
135  const geometry_msgs::PoseStamped& goal,
136  std::vector<geometry_msgs::PoseStamped>& plan);
137 
143  double getPointPotential(const geometry_msgs::Point& world_point);
144 
150  bool validPointPotential(const geometry_msgs::Point& world_point);
151 
158  bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
159 
163  void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path);
164 
165  bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
166 
167  protected:
168 
173  std::string frame_id_;
176 
177  private:
178  void mapToWorld(double mx, double my, double& wx, double& wy);
179  bool worldToMap(double wx, double wy, double& mx, double& my);
180  void clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my);
181  void publishPotential(float* potential);
182 
184  std::string tf_prefix_;
185  boost::mutex mutex_;
187 
192 
196 
197  void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value);
198  unsigned char* cost_array_;
200  unsigned int start_x_, start_y_, end_x_, end_y_;
201 
204 
205  dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig> *dsrv_;
206  void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level);
207 
208 };
209 
210 } //end namespace global_planner
211 
212 #endif
void clearRobotCell(const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my)
void publishPotential(float *potential)
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Given a goal pose in the world, compute a plan.
void mapToWorld(double mx, double my, double &wx, double &wy)
void outlineMap(unsigned char *costarr, int nx, int ny, unsigned char value)
bool computePotential(const geometry_msgs::Point &world_point)
Computes the full navigation function for the map given a point in the world to start from...
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the PlannerCore object.
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
Definition: planner_core.h:172
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
PotentialCalculator * p_calc_
Definition: planner_core.h:188
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
bool validPointPotential(const geometry_msgs::Point &world_point)
Check for a valid potential value at a given point in the world (Note: You should call computePotenti...
bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Compute a plan to a goal after the potential for a start point has already been computed (Note: You s...
bool worldToMap(double wx, double wy, double &mx, double &my)
GlobalPlanner()
Default constructor for the PlannerCore object.
double getPointPotential(const geometry_msgs::Point &world_point)
Get the potential, or naviagation cost, at a given point in the world (Note: You should call computeP...
OrientationFilter * orientation_filter_
Definition: planner_core.h:191
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
ros::ServiceServer make_plan_srv_
Definition: planner_core.h:186
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
Definition: planner_core.h:205


global_planner
Author(s): David Lu!!
autogenerated on Sun Mar 3 2019 03:44:42