1 #ifndef RAPP_PATH_PLANNER_NODE
2 #define RAPP_PATH_PLANNER_NODE
5 #include <geometry_msgs/PoseStamped.h>
6 #include <nav_msgs/Path.h>
28 std::string
setSequenceNR(ros::NodeHandle &nh_,
int pathPlanningThreads_);
39 bool configureSequence(std::string seq_nr, std::string map_path, std::string robot_type, std::string algorithm, ros::NodeHandle &nh_);
56 navfn::MakeNavPlanResponse
startSequence(std::string seq_nr, geometry_msgs::PoseStamped request_start, geometry_msgs::PoseStamped request_goal, ros::NodeHandle &nh_);
Class that implements a path planning algorithm based on global_planner and map_server ROS nodes...
std::string setSequenceNR(ros::NodeHandle &nh_, int pathPlanningThreads_)
Determines next planning seqence (which global_planner and map_server should be used) ...
bool configureSequence(std::string seq_nr, std::string map_path, std::string robot_type, std::string algorithm, ros::NodeHandle &nh_)
Configures sequence. Sets map, approprate costmap parameters for specified robot type, sets global_planner to use detemined algorithm.
PathPlanner(void)
Default constructor.
navfn::MakeNavPlanResponse startSequence(std::string seq_nr, geometry_msgs::PoseStamped request_start, geometry_msgs::PoseStamped request_goal, ros::NodeHandle &nh_)
Starts planning service of determined planning sequence.