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
PathPlanning Class Reference

#include <path_planning.h>

Collaboration diagram for PathPlanning:

Public Member Functions

 PathPlanning (void)
 Default constructor. More...
 
 ~PathPlanning (void)
 
bool pathPlanningCallback (rapp_platform_ros_communications::PathPlanningRosSrv::Request &req, rapp_platform_ros_communications::PathPlanningRosSrv::Response &res)
 Determines next planning seqence (which global_planner and map_server should be used) More...
 
bool uploadMapCallback (rapp_platform_ros_communications::MapServerUploadMapRosSrv::Request &req, rapp_platform_ros_communications::MapServerUploadMapRosSrv::Response &res)
 Upload map to RAPP Platform. More...
 

Private Attributes

std::vector< pid_t > GP_pIDs
 
const char * homedir
 
std::vector< pid_t > MS_pIDs
 
std::vector
< geometry_msgs::PoseStamped > 
new_path
 
ros::NodeHandle nh_
 
PathPlanner path_planner_
 
ros::ServiceServer pathPlanningService_
 
int pathPlanningThreads_
 
std::vector< ros::ServiceServer > pathPlanningThreadServices_
 
std::string pathPlanningTopic_
 
double pose_dist_
 
pid_t TP_pID
 
ros::ServiceServer uploadMapService_
 
std::string uploadMapTopic_
 

Detailed Description

Definition at line 23 of file path_planning.h.

Constructor & Destructor Documentation

PathPlanning::PathPlanning ( void  )

Default constructor.

Definition at line 181 of file path_planning.cpp.

PathPlanning::~PathPlanning ( void  )

Definition at line 31 of file path_planning.cpp.

Member Function Documentation

bool PathPlanning::pathPlanningCallback ( rapp_platform_ros_communications::PathPlanningRosSrv::Request &  req,
rapp_platform_ros_communications::PathPlanningRosSrv::Response &  res 
)

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

Parameters
[navfn::MakeNavPlanRequest]&req: [std::string] req.user_name - Determine user name - owner of the environment map [std::string] req.map_name - Contains path to the desired map [std::string] req.robot_type - Contains type of the robot. It is required to determine it's parameters (footprint etc.) [std::string] req.algorithm - Contains path planning algorithm name [geometry_msgs/PoseStamped] req.start - Contains start pose of the robot [geometry_msgs/PoseStamped] req.goal - Contains goal pose of the robot
[navfn::MakeNavPlanResponse]&res: [uint8] res.plan_found: 0 : path cannot be planned. 1 : path found 2 : wrong map name 3 : wrong robot type 4 : wrong algorithm [std::string] res.error_message : error explenation [geometry_msgs/PoseStamped[]] res.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 302 of file path_planning.cpp.

bool PathPlanning::uploadMapCallback ( rapp_platform_ros_communications::MapServerUploadMapRosSrv::Request &  req,
rapp_platform_ros_communications::MapServerUploadMapRosSrv::Response &  res 
)

Upload map to RAPP Platform.

Parameters
&req[std::string] user_name, [std::string] map_name, [float32] resolution, [float32[]] origin, int16 negate, [float32] occupied_thresh, [float32] free_thresh, [uint32] file_size, [char[]] data,
&res[byte] status ,
Returns
[bool] true-> success, false-> failure.

Definition at line 242 of file path_planning.cpp.

Member Data Documentation

std::vector<pid_t> PathPlanning::GP_pIDs
private

Definition at line 74 of file path_planning.h.

const char* PathPlanning::homedir
private

Definition at line 69 of file path_planning.h.

std::vector<pid_t> PathPlanning::MS_pIDs
private

Definition at line 75 of file path_planning.h.

std::vector<geometry_msgs::PoseStamped> PathPlanning::new_path
private

Definition at line 82 of file path_planning.h.

ros::NodeHandle PathPlanning::nh_
private

Definition at line 67 of file path_planning.h.

PathPlanner PathPlanning::path_planner_
private

Definition at line 83 of file path_planning.h.

ros::ServiceServer PathPlanning::pathPlanningService_
private

Definition at line 71 of file path_planning.h.

int PathPlanning::pathPlanningThreads_
private

Definition at line 80 of file path_planning.h.

std::vector<ros::ServiceServer> PathPlanning::pathPlanningThreadServices_
private

Definition at line 73 of file path_planning.h.

std::string PathPlanning::pathPlanningTopic_
private

Definition at line 78 of file path_planning.h.

double PathPlanning::pose_dist_
private

Definition at line 81 of file path_planning.h.

pid_t PathPlanning::TP_pID
private

Definition at line 76 of file path_planning.h.

ros::ServiceServer PathPlanning::uploadMapService_
private

Definition at line 72 of file path_planning.h.

std::string PathPlanning::uploadMapTopic_
private

Definition at line 79 of file path_planning.h.


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