1 #ifndef RAPP_PATH_PLANNING_NODE
2 #define RAPP_PATH_PLANNING_NODE
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"
15 #include <boost/lexical_cast.hpp>
17 #include <ros/service_manager.h>
20 #include <sys/types.h>
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
82 std::vector<geometry_msgs::PoseStamped>
new_path;
std::vector< pid_t > GP_pIDs
Class that implements a path planning algorithm based on global_planner and map_server ROS nodes...
std::string uploadMapTopic_
std::vector< geometry_msgs::PoseStamped > new_path
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) ...
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_
std::string pathPlanningTopic_
PathPlanner path_planner_
ros::ServiceServer uploadMapService_
PathPlanning(void)
Default constructor.
std::vector< pid_t > MS_pIDs
ros::ServiceServer pathPlanningService_