Go to the documentation of this file.
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>
48 #include <nav_msgs/GetPlan.h>
49 #include <dynamic_reconfigure/server.h>
54 #include <global_planner/GlobalPlannerConfig.h>
102 bool makePlan(
const geometry_msgs::PoseStamped&
start,
const geometry_msgs::PoseStamped&
goal,
103 std::vector<geometry_msgs::PoseStamped>& plan);
113 bool makePlan(
const geometry_msgs::PoseStamped&
start,
const geometry_msgs::PoseStamped&
goal,
double tolerance,
114 std::vector<geometry_msgs::PoseStamped>& plan);
134 const geometry_msgs::PoseStamped&
goal,
135 std::vector<geometry_msgs::PoseStamped>& plan);
162 void publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path);
164 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
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);
195 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);
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...
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 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...
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
PotentialCalculator * p_calc_
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
GlobalPlanner()
Default constructor for the PlannerCore object.
void publishPotential(float *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.
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
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.
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
void outlineMap(unsigned char *costarr, int nx, int ny, unsigned char value)
ros::ServiceServer make_plan_srv_
bool worldToMap(double wx, double wy, double &mx, double &my)
ros::Publisher potential_pub_
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
OrientationFilter * orientation_filter_
void mapToWorld(double mx, double my, double &wx, double &wy)
double default_tolerance_
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
void clearRobotCell(const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the PlannerCore object.
global_planner
Author(s): David Lu!!
autogenerated on Mon Mar 6 2023 03:50:40