#include <planner_core.h>

Public Member Functions | |
| bool | findPath (std::vector< std::pair< float, float > > *path, int init_x, int init_y, int goal_x, int goal_y, DynamicVoronoi *voronoi, bool check_is_voronoi_cell, bool stop_at_voronoi) |
| void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
| Initialization function for the PlannerCore object. | |
| void | initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) |
| 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 | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, 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 | publishPlan (const std::vector< geometry_msgs::PoseStamped > &path) |
| Publish a path for visualization purposes. | |
| void | publishVoronoiGrid (DynamicVoronoi *voronoi) |
| void | smoothPath (std::vector< std::pair< float, float > > *path) |
| VoronoiPlanner () | |
| Default constructor for the PlannerCore object. | |
| VoronoiPlanner (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) | |
| Constructor for the PlannerCore object. | |
| ~VoronoiPlanner () | |
| Default deconstructor for the PlannerCore object. | |
Protected Attributes | |
| costmap_2d::Costmap2D * | costmap_ |
| Store a copy of the current costmap in costmap. Called by makePlan. | |
| std::string | frame_id_ |
| bool | initialized_ |
| ros::Publisher | plan_pub_ |
| bool | publish_voronoi_grid_ |
| bool | smooth_path_ |
| ros::Publisher | voronoi_grid_pub_ |
| float | weight_data_ |
| float | weight_smooth_ |
Private Member Functions | |
| void | clearRobotCell (const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my) |
| void | costmapUpdateCallback (const map_msgs::OccupancyGridUpdate::ConstPtr &msg) |
| void | mapToWorld (double mx, double my, double &wx, double &wy) |
| void | outlineMap (unsigned char *costarr, int nx, int ny, unsigned char value) |
| void | reconfigureCB (voronoi_planner::VoronoiPlannerConfig &config, uint32_t level) |
| bool | worldToMap (double wx, double wy, double &mx, double &my) |
Private Attributes | |
| unsigned char * | cost_array_ |
| double | default_tolerance_ |
| dynamic_reconfigure::Server < voronoi_planner::VoronoiPlannerConfig > * | dsrv_ |
| unsigned int | end_x_ |
| unsigned int | end_y_ |
| ros::ServiceServer | make_plan_srv_ |
| boost::mutex | mutex_ |
| double | planner_window_x_ |
| double | planner_window_y_ |
| unsigned int | start_x_ |
| unsigned int | start_y_ |
| std::string | tf_prefix_ |
| DynamicVoronoi | voronoi_ |
Definition at line 31 of file planner_core.h.
Default constructor for the PlannerCore object.
Definition at line 75 of file planner_core.cpp.
| voronoi_planner::VoronoiPlanner::VoronoiPlanner | ( | std::string | name, |
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | frame_id | ||
| ) |
Constructor for the PlannerCore object.
| name | The name of this planner |
| costmap | A pointer to the costmap to use |
| frame_id | Frame of the costmap |
Definition at line 80 of file planner_core.cpp.
Default deconstructor for the PlannerCore object.
Definition at line 88 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::clearRobotCell | ( | const tf::Stamped< tf::Pose > & | global_pose, |
| unsigned int | mx, | ||
| unsigned int | my | ||
| ) | [private] |
Definition at line 145 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::costmapUpdateCallback | ( | const map_msgs::OccupancyGridUpdate::ConstPtr & | msg | ) | [private] |
Definition at line 131 of file planner_core.cpp.
| bool voronoi_planner::VoronoiPlanner::findPath | ( | std::vector< std::pair< float, float > > * | path, |
| int | init_x, | ||
| int | init_y, | ||
| int | goal_x, | ||
| int | goal_y, | ||
| DynamicVoronoi * | voronoi, | ||
| bool | check_is_voronoi_cell, | ||
| bool | stop_at_voronoi | ||
| ) |
Definition at line 450 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::initialize | ( | std::string | name, |
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) | [virtual] |
Initialization function for the PlannerCore object.
| name | The name of this planner |
| costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Implements nav_core::BaseGlobalPlanner.
Definition at line 92 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::initialize | ( | std::string | name, |
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | frame_id | ||
| ) |
Definition at line 96 of file planner_core.cpp.
| bool voronoi_planner::VoronoiPlanner::makePlan | ( | const geometry_msgs::PoseStamped & | start, |
| const geometry_msgs::PoseStamped & | goal, | ||
| std::vector< geometry_msgs::PoseStamped > & | plan | ||
| ) | [virtual] |
Given a goal pose in the world, compute a plan.
| start | The start pose |
| goal | The goal pose |
| plan | The plan... filled by the planner |
Implements nav_core::BaseGlobalPlanner.
Definition at line 188 of file planner_core.cpp.
| bool voronoi_planner::VoronoiPlanner::makePlan | ( | const geometry_msgs::PoseStamped & | start, |
| const geometry_msgs::PoseStamped & | goal, | ||
| double | tolerance, | ||
| std::vector< geometry_msgs::PoseStamped > & | plan | ||
| ) |
Given a goal pose in the world, compute a plan.
| start | The start pose |
| goal | The goal pose |
| tolerance | The tolerance on the goal point for the planner |
| plan | The plan... filled by the planner |
Definition at line 193 of file planner_core.cpp.
| bool voronoi_planner::VoronoiPlanner::makePlanService | ( | nav_msgs::GetPlan::Request & | req, |
| nav_msgs::GetPlan::Response & | resp | ||
| ) |
Definition at line 156 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::mapToWorld | ( | double | mx, |
| double | my, | ||
| double & | wx, | ||
| double & | wy | ||
| ) | [private] |
Definition at line 165 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::outlineMap | ( | unsigned char * | costarr, |
| int | nx, | ||
| int | ny, | ||
| unsigned char | value | ||
| ) | [private] |
Definition at line 60 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::publishPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | path | ) |
Publish a path for visualization purposes.
Definition at line 668 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::publishVoronoiGrid | ( | DynamicVoronoi * | voronoi | ) |
Definition at line 692 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::reconfigureCB | ( | voronoi_planner::VoronoiPlannerConfig & | config, |
| uint32_t | level | ||
| ) | [private] |
Definition at line 137 of file planner_core.cpp.
| void voronoi_planner::VoronoiPlanner::smoothPath | ( | std::vector< std::pair< float, float > > * | path | ) |
Definition at line 628 of file planner_core.cpp.
| bool voronoi_planner::VoronoiPlanner::worldToMap | ( | double | wx, |
| double | wy, | ||
| double & | mx, | ||
| double & | my | ||
| ) | [private] |
Definition at line 171 of file planner_core.cpp.
unsigned char* voronoi_planner::VoronoiPlanner::cost_array_ [private] |
Definition at line 132 of file planner_core.h.
Store a copy of the current costmap in costmap. Called by makePlan.
Definition at line 105 of file planner_core.h.
double voronoi_planner::VoronoiPlanner::default_tolerance_ [private] |
Definition at line 124 of file planner_core.h.
dynamic_reconfigure::Server<voronoi_planner::VoronoiPlannerConfig>* voronoi_planner::VoronoiPlanner::dsrv_ [private] |
Definition at line 136 of file planner_core.h.
unsigned int voronoi_planner::VoronoiPlanner::end_x_ [private] |
Definition at line 133 of file planner_core.h.
unsigned int voronoi_planner::VoronoiPlanner::end_y_ [private] |
Definition at line 133 of file planner_core.h.
std::string voronoi_planner::VoronoiPlanner::frame_id_ [protected] |
Definition at line 106 of file planner_core.h.
bool voronoi_planner::VoronoiPlanner::initialized_ [protected] |
Definition at line 108 of file planner_core.h.
Definition at line 127 of file planner_core.h.
boost::mutex voronoi_planner::VoronoiPlanner::mutex_ [private] |
Definition at line 126 of file planner_core.h.
Definition at line 107 of file planner_core.h.
double voronoi_planner::VoronoiPlanner::planner_window_x_ [private] |
Definition at line 124 of file planner_core.h.
double voronoi_planner::VoronoiPlanner::planner_window_y_ [private] |
Definition at line 124 of file planner_core.h.
bool voronoi_planner::VoronoiPlanner::publish_voronoi_grid_ [protected] |
Definition at line 110 of file planner_core.h.
bool voronoi_planner::VoronoiPlanner::smooth_path_ [protected] |
Definition at line 113 of file planner_core.h.
unsigned int voronoi_planner::VoronoiPlanner::start_x_ [private] |
Definition at line 133 of file planner_core.h.
unsigned int voronoi_planner::VoronoiPlanner::start_y_ [private] |
Definition at line 133 of file planner_core.h.
std::string voronoi_planner::VoronoiPlanner::tf_prefix_ [private] |
Definition at line 125 of file planner_core.h.
Definition at line 129 of file planner_core.h.
Definition at line 111 of file planner_core.h.
float voronoi_planner::VoronoiPlanner::weight_data_ [protected] |
Definition at line 114 of file planner_core.h.
float voronoi_planner::VoronoiPlanner::weight_smooth_ [protected] |
Definition at line 115 of file planner_core.h.