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
path_planning.h
Go to the documentation of this file.
1 #ifndef RAPP_PATH_PLANNING_NODE
2 #define RAPP_PATH_PLANNING_NODE
3 
4 #include "ros/ros.h"
5 #include "ros/package.h"
6 #include <navfn/MakeNavPlan.h>
7 #include <navfn/MakeNavPlanResponse.h>
8 #include <rapp_platform_ros_communications/PathPlanningRosSrv.h>
9 #include "rapp_platform_ros_communications/MapServerGetMapRosSrv.h"
10 #include "rapp_platform_ros_communications/Costmap2dRosSrv.h"
11 #include "rapp_platform_ros_communications/MapServerUploadMapRosSrv.h"
12 #include <signal.h>
14 //converting variables
15 #include <boost/lexical_cast.hpp>
16 // for service manager -> determine if service is active
17 #include <ros/service_manager.h>
18 //get rapp-platform home directory
19 #include <unistd.h>
20 #include <sys/types.h>
21 #include <pwd.h>
22 
24 {
25  public:
26 
30  PathPlanning(void);
31  ~PathPlanning(void);
39  bool uploadMapCallback(rapp_platform_ros_communications::MapServerUploadMapRosSrv::Request &req,
40  rapp_platform_ros_communications::MapServerUploadMapRosSrv::Response &res);
61  rapp_platform_ros_communications::PathPlanningRosSrv::Request& req,
62  rapp_platform_ros_communications::PathPlanningRosSrv::Response& res
63  );
64 
65  private:
66  // The ROS node handle
67  ros::NodeHandle nh_;
68  // RAPP-platform home_dir
69  const char *homedir;
70  // The service server
71  ros::ServiceServer pathPlanningService_;
72  ros::ServiceServer uploadMapService_;
73  std::vector<ros::ServiceServer> pathPlanningThreadServices_;
74  std::vector<pid_t> GP_pIDs;
75  std::vector<pid_t> MS_pIDs;
76  pid_t TP_pID;
77  // Topic nomeclarure
78  std::string pathPlanningTopic_;
79  std::string uploadMapTopic_;
81  double pose_dist_;
82  std::vector<geometry_msgs::PoseStamped> new_path;
84 };
85 
86 #endif
std::vector< pid_t > GP_pIDs
Definition: path_planning.h:74
Class that implements a path planning algorithm based on global_planner and map_server ROS nodes...
Definition: path_planner.h:12
std::string uploadMapTopic_
Definition: path_planning.h:79
std::vector< geometry_msgs::PoseStamped > new_path
Definition: path_planning.h:82
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) ...
int pathPlanningThreads_
Definition: path_planning.h:80
bool uploadMapCallback(rapp_platform_ros_communications::MapServerUploadMapRosSrv::Request &req, rapp_platform_ros_communications::MapServerUploadMapRosSrv::Response &res)
Upload map to RAPP Platform.
std::vector< ros::ServiceServer > pathPlanningThreadServices_
Definition: path_planning.h:73
double pose_dist_
Definition: path_planning.h:81
std::string pathPlanningTopic_
Definition: path_planning.h:78
ros::NodeHandle nh_
Definition: path_planning.h:67
PathPlanner path_planner_
Definition: path_planning.h:83
ros::ServiceServer uploadMapService_
Definition: path_planning.h:72
PathPlanning(void)
Default constructor.
std::vector< pid_t > MS_pIDs
Definition: path_planning.h:75
const char * homedir
Definition: path_planning.h:69
ros::ServiceServer pathPlanningService_
Definition: path_planning.h:71