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 <vector>
48 #include <nav_msgs/GetPlan.h>
49 #include <dynamic_reconfigure/server.h>
54 #include <global_planner/GlobalPlannerConfig.h>
55 
56 namespace global_planner {
57 
58 class Expander;
59 class GridPath;
60 
67  public:
71  GlobalPlanner();
72 
79  GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
80 
85 
91  void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
92 
93  void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
94 
102  bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
103  std::vector<geometry_msgs::PoseStamped>& plan);
104 
113  bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance,
114  std::vector<geometry_msgs::PoseStamped>& plan);
115 
121  bool computePotential(const geometry_msgs::Point& world_point);
122 
133  bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y,
134  const geometry_msgs::PoseStamped& goal,
135  std::vector<geometry_msgs::PoseStamped>& plan);
136 
142  double getPointPotential(const geometry_msgs::Point& world_point);
143 
149  bool validPointPotential(const geometry_msgs::Point& world_point);
150 
157  bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
158 
162  void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path);
163 
164  bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
165 
166  protected:
167 
172  std::string frame_id_;
175 
176  private:
177  void mapToWorld(double mx, double my, double& wx, double& wy);
178  bool worldToMap(double wx, double wy, double& mx, double& my);
179  void clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my);
180  void publishPotential(float* potential);
181 
183  boost::mutex mutex_;
185 
190 
194 
195  void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value);
196 
198  unsigned int start_x_, start_y_, end_x_, end_y_;
199 
202 
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
global_planner::GlobalPlanner::getPointPotential
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...
orientation_filter.h
global_planner::GlobalPlanner::publish_scale_
int publish_scale_
Definition: planner_core.h:193
global_planner::GlobalPlanner::getPlanFromPotential
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...
Definition: planner_core.cpp:382
global_planner::GlobalPlanner::potential_array_
float * potential_array_
Definition: planner_core.h:197
global_planner
Definition: astar.h:46
ros::Publisher
global_planner::GlobalPlanner::validPointPotential
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...
global_planner::GlobalPlanner::start_x_
unsigned int start_x_
Definition: planner_core.h:198
global_planner::GlobalPlanner::start_y_
unsigned int start_y_
Definition: planner_core.h:198
ros.h
costmap_2d.h
global_planner::GlobalPlanner::reconfigureCB
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
Definition: planner_core.cpp:198
global_planner::GlobalPlanner::p_calc_
PotentialCalculator * p_calc_
Definition: planner_core.h:186
costmap_2d::Costmap2D
global_planner::GlobalPlanner::publishPlan
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
Definition: planner_core.cpp:360
global_planner::GlobalPlanner::planner_
Expander * planner_
Definition: planner_core.h:187
ros::ServiceServer
global_planner::GlobalPlanner
Definition: planner_core.h:66
global_planner::OrientationFilter
Definition: orientation_filter.h:80
global_planner::GlobalPlanner::GlobalPlanner
GlobalPlanner()
Default constructor for the PlannerCore object.
Definition: planner_core.cpp:105
global_planner::GlobalPlanner::publishPotential
void publishPotential(float *potential)
Definition: planner_core.cpp:428
global_planner::GlobalPlanner::planner_window_x_
double planner_window_x_
Definition: planner_core.h:182
global_planner::GlobalPlanner::end_y_
unsigned int end_y_
Definition: planner_core.h:198
expander.h
global_planner::GlobalPlanner::computePotential
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.
global_planner::GlobalPlanner::dsrv_
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
Definition: planner_core.h:205
start
int start[2]
goal
int goal[2]
global_planner::GlobalPlanner::publish_potential_
bool publish_potential_
Definition: planner_core.h:191
global_planner::GlobalPlanner::end_x_
unsigned int end_x_
Definition: planner_core.h:198
global_planner::GlobalPlanner::makePlan
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.
Definition: planner_core.cpp:249
global_planner::GlobalPlanner::makePlanService
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
Definition: planner_core.cpp:219
global_planner::GlobalPlanner::outlineMap
void outlineMap(unsigned char *costarr, int nx, int ny, unsigned char value)
Definition: planner_core.cpp:90
global_planner::GlobalPlanner::make_plan_srv_
ros::ServiceServer make_plan_srv_
Definition: planner_core.h:184
global_planner::Expander
Definition: expander.h:81
global_planner::GlobalPlanner::worldToMap
bool worldToMap(double wx, double wy, double &mx, double &my)
Definition: planner_core.cpp:233
global_planner::GlobalPlanner::potential_pub_
ros::Publisher potential_pub_
Definition: planner_core.h:192
global_planner::GlobalPlanner::plan_pub_
ros::Publisher plan_pub_
Definition: planner_core.h:173
global_planner::PotentialCalculator
Definition: potential_calculator.h:81
global_planner::Traceback
Definition: traceback.h:81
global_planner::GlobalPlanner::convert_offset_
float convert_offset_
Definition: planner_core.h:201
base_global_planner.h
global_planner::GlobalPlanner::~GlobalPlanner
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
Definition: planner_core.cpp:117
global_planner::GlobalPlanner::old_navfn_behavior_
bool old_navfn_behavior_
Definition: planner_core.h:200
global_planner::GlobalPlanner::allow_unknown_
bool allow_unknown_
Definition: planner_core.h:174
global_planner::GlobalPlanner::orientation_filter_
OrientationFilter * orientation_filter_
Definition: planner_core.h:189
global_planner::GlobalPlanner::mapToWorld
void mapToWorld(double mx, double my, double &wx, double &wy)
Definition: planner_core.cpp:228
global_planner::GlobalPlanner::path_maker_
Traceback * path_maker_
Definition: planner_core.h:188
global_planner::GlobalPlanner::planner_window_y_
double planner_window_y_
Definition: planner_core.h:182
global_planner::GlobalPlanner::frame_id_
std::string frame_id_
Definition: planner_core.h:172
global_planner::GlobalPlanner::initialized_
bool initialized_
Definition: planner_core.h:174
global_planner::GlobalPlanner::mutex_
boost::mutex mutex_
Definition: planner_core.h:183
global_planner::GlobalPlanner::default_tolerance_
double default_tolerance_
Definition: planner_core.h:182
global_planner::GlobalPlanner::outline_map_
bool outline_map_
Definition: planner_core.h:203
nav_core::BaseGlobalPlanner
potential_calculator.h
global_planner::GlobalPlanner::costmap_
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
Definition: planner_core.h:171
costmap_2d::Costmap2DROS
global_planner::GlobalPlanner::clearRobotCell
void clearRobotCell(const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my)
Definition: planner_core.cpp:208
traceback.h
global_planner::GlobalPlanner::initialize
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the PlannerCore object.
Definition: planner_core.cpp:128


global_planner
Author(s): David Lu!!
autogenerated on Mon Mar 6 2023 03:50:40