#include <path_planning.h>
|
| 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...
|
|
Definition at line 23 of file path_planning.h.
PathPlanning::PathPlanning |
( |
void |
| ) |
|
PathPlanning::~PathPlanning |
( |
void |
| ) |
|
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.
std::vector<pid_t> PathPlanning::GP_pIDs |
|
private |
const char* PathPlanning::homedir |
|
private |
std::vector<pid_t> PathPlanning::MS_pIDs |
|
private |
std::vector<geometry_msgs::PoseStamped> PathPlanning::new_path |
|
private |
ros::NodeHandle PathPlanning::nh_ |
|
private |
ros::ServiceServer PathPlanning::pathPlanningService_ |
|
private |
int PathPlanning::pathPlanningThreads_ |
|
private |
std::vector<ros::ServiceServer> PathPlanning::pathPlanningThreadServices_ |
|
private |
std::string PathPlanning::pathPlanningTopic_ |
|
private |
double PathPlanning::pose_dist_ |
|
private |
pid_t PathPlanning::TP_pID |
|
private |
ros::ServiceServer PathPlanning::uploadMapService_ |
|
private |
std::string PathPlanning::uploadMapTopic_ |
|
private |
The documentation for this class was generated from the following files:
- /home/travis/rapp_temp/rapp-platform/rapp_path_planning/rapp_path_planning/include/path_planning/path_planning.h
- /home/travis/rapp_temp/rapp-platform/rapp_path_planning/rapp_path_planning/src/path_planning.cpp