40 #define POT_HIGH 1.0e10 // unassigned cell potential 43 #include <geometry_msgs/PoseStamped.h> 44 #include <geometry_msgs/Point.h> 45 #include <nav_msgs/Path.h> 49 #include <nav_msgs/GetPlan.h> 50 #include <dynamic_reconfigure/server.h> 55 #include <global_planner/GlobalPlannerConfig.h> 103 bool makePlan(
const geometry_msgs::PoseStamped&
start,
const geometry_msgs::PoseStamped&
goal,
104 std::vector<geometry_msgs::PoseStamped>& plan);
114 bool makePlan(
const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal,
double tolerance,
115 std::vector<geometry_msgs::PoseStamped>& plan);
135 const geometry_msgs::PoseStamped& goal,
136 std::vector<geometry_msgs::PoseStamped>& plan);
163 void publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path);
165 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
178 void mapToWorld(
double mx,
double my,
double& wx,
double& wy);
179 bool worldToMap(
double wx,
double wy,
double& mx,
double& my);
197 void outlineMap(
unsigned char* costarr,
int nx,
int ny,
unsigned char value);
205 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig> *
dsrv_;
206 void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level);
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 visualize_potential_
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.
double default_tolerance_
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
PotentialCalculator * p_calc_
unsigned char * cost_array_
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_
ros::Publisher potential_pub_
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
ros::ServiceServer make_plan_srv_
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_