RAPP Platform  v0.6.0
RAPP Platform is a collection of ROS nodes and back-end processes that aim to deliver ready-to-use generic services to robots
 All Classes Namespaces Files Functions Variables Macros
PathPlanner Class Reference

Class that implements a path planning algorithm based on global_planner and map_server ROS nodes. More...

#include <path_planner.h>

Public Member Functions

 PathPlanner (void)
 Default constructor. More...
 
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. More...
 
std::string setSequenceNR (ros::NodeHandle &nh_, int pathPlanningThreads_)
 Determines next planning seqence (which global_planner and map_server should be used) More...
 
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. More...
 

Detailed Description

Class that implements a path planning algorithm based on global_planner and map_server ROS nodes.

Definition at line 12 of file path_planner.h.

Constructor & Destructor Documentation

PathPlanner::PathPlanner ( void  )

Default constructor.

Definition at line 4 of file path_planner.cpp.

Member Function Documentation

bool PathPlanner::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.

Parameters
seq_nr[std::string] ID of current sequence,
map_path[std::string] Path to the map that should be passed to global_planner,
robot_type[std::string] Name of robot_type. It is used to configure costmap,
algorithm[std::string] Name of algorithm that should be used by global_planner,
&nh_[ros::NodeHandle] node handler for getParam() method,
Returns
[bool] Returns if sequence was configured correctly. Returns false if PathPlanner could not configure sequence in 5 sec.

Definition at line 26 of file path_planner.cpp.

std::string PathPlanner::setSequenceNR ( ros::NodeHandle &  nh_,
int  pathPlanningThreads_ 
)

Determines next planning seqence (which global_planner and map_server should be used)

Parameters
&nh_[ros::NodeHandle] node handler for getParam() method,
pathPlanningThreads_[int] Number of planning sequences,
Returns
[std::string] Next sequence nr.

Definition at line 9 of file path_planner.cpp.

navfn::MakeNavPlanResponse PathPlanner::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.

Parameters
start[geometry_msgs::PoseStamped] Robot start pose,
finish[geometry_msgs::PoseStamped] Robot goal pose.
Returns
[navfn::MakeNavPlanResponse]: -> plan_found: 0 : path cannot be planned. 1 : path found 2 : wrong map name 3 : wrong robot type 4 : wrong algorithm -> error_message : error explenation -> path : if plan_found is true, this is an array of waypoints from start to goal, where the first one equals start and the last one equals goal vector of PoseStamped objects

Definition at line 137 of file path_planner.cpp.


The documentation for this class was generated from the following files: