Skip to content
dudekw edited this page Jun 9, 2016 · 6 revisions
Rapp_path_planner incon **List of contents** ---------- 1. [Components](https://github.com/rapp-project/rapp-platform/wiki/#components) 2. [Package launch] (https://github.com/rapp-project/rapp-platform/wiki/#package-launch) 3. [Prepare new map manually] (https://github.com/rapp-project/rapp-platform/wiki/#prepare-new-map-manually) 4. [ROS services](https://github.com/rapp-project/rapp-platform/wiki/#ros-services) 5. [WEB services](https://github.com/rapp-project/rapp-platform/wiki/#web-services)

##Components

1. rapp_path_planning

Rapp_path_planning is used in the RAPP case to plan path from given pose to given goal. User can costomize the path planning module with following parameters:

  • pebuild map - avaliable maps are stored here,
  • planning algorithm - for now, only dijkstra is avaliable,
  • robot type - customizes costmap for planning module. For now only NAO is supported.

2. rapp_map_server

Rapp_map_server delivers prebuild maps to rapp_path_planning component. All avaliable maps are contained here.

This component is based on the ROS package: map_server. The rapp_map_server reads .png and .yaml files and publishes map as OccupacyGrid data. RAPP case needs run-time changing map publication, thus the rapp_map_server extands map_server functionality. The rapp_map_server enables user run-time changes of map. It subscribes to ROS parameter: rospy.set_param(nodeName+"/setMap", map_path) and publishes the map specified in map_path. Examplary map changing request is presented below.

nodename = rospy.get_name()
map_path = "/home/rapp/rapp_platform/rapp-platform-catkin-ws/src/rapp-platform/rapp_map_server/maps/empty.yaml"
rospy.set_param(nodename+/setMap, map_path)

A ROS service exists to store new maps in each user's workspace, called upload_map. Then each application can invoke the planPath2D service, providing the map's name (among others) as input argument.

##Package launch

Standard launch

Launches the path planning node and can be launched using

roslaunch rapp_path_planning path_planning.launch

Prepare new map manually

New map files have to be compatible with the map_server package. Detailed description of files and their parameters can be found here. Exemplary map files can be found here.

  1. Prepare PNG file:
    a) Dimension desired area,
    b) Scale measurements by a desired factor. Chosen factor represents the map resolution!
    c) Draw obstacles and walls with black color carefully. Size of obstacles and walls is very important and every pixel makes difference!
    d) Rest of the map should be left white.
    e) Export your image to the .png file. Name of the file is important, so choose wisely!
  2. Write configuration file:
    a) Create empty file: <map_name>.yaml
    b) Open the file and set following configuration parameters:
# Name of .png file.
image: <png_file_name> # example -> image: test_map.png

# The map's resolution [meters / pixel]
resolution: <resolution> # example -> resolution: 0.1

# The map's origin. 2D pose of the map origin. [x, y, yaw] 
origin: <map_origin> # example -> origin: [0.0, 0.0, 0.0]

# Whether the occupied / unoccupied pixels must be negated
negate: <negate> # example -> negate: 0

# Pixels with occupancy probability greater than this threshold are considered completely occupied.
occupied_thresh: <value> # example -> occupied_thresh: 0.65

# Pixels with occupancy probability less than this threshold are considered completely free.
free_thresh: <value> # example -> free_thresh: 0.196

##ROS Services

2D path planning

Service URL: /rapp/rapp_path_planning/planPath2D

Service type:

# Contains name to the desired map
string map_name
# Contains type of the robot. It is required to determine it's parameters (footprint etc.)
string robot_type
# Contains path planning algorithm name
string algorithm
# Contains start pose of the robot
geometry_msgs/PoseStamped start
# Contains goal pose of the robot
geometry_msgs/PoseStamped goal
---
# status of the service
# plan_found:
#          * 0 : path cannot be planned.
#          * 1 : path found 
#          * 2 : wrong map name
#          * 3 : wrong robot type
#          * 4 : wrong algorithm


uint8 plan_found
# error_message : error explanation
string error_message
# path : vector of PoseStamped objects
# 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
geometry_msgs/PoseStamped[] path

map file upload

Service URL: /rapp/rapp_path_planning/upload_map

Service type:

# The end user's username, since the uploaded map is personal 
string user_name
# The map's name. Must be unique for this user
string map_name
# The map's resolution
float32 resolution
# ROS-specific: The map's origin
float32[] origin
# ROS-specific: Whether the occupied / unoccupied pixels must be negated
int16 negate
# Occupied threshold
float32 occupied_thresh
# Unoccupied threshold
float32 free_thresh
# File size for sanity checks
uint32 file_size
# The map data
char[] data
---
byte status

More information on the Occupancy Grid Map representation can be found here

##Web services

Path planning 2D

URL

localhost:9001/hop/path_planning_path_2d

Input / Output

Input = {
  "map_name": “THE_PRESTORED_MAP_NAME”,
  "robot_type": "Nao",
  "algorithm": "dijkstra",
  "start": {x: 0, y: 10},
  "goal": {x: 10, y: 0}
}
Output = {
  "plan_found": 0,
  "path": [{x: 0, y: 10}, {x: ... ],
  "error": ""
}

Upload map

URL

localhost:9001/hop/path_planning_upload_map

Input / Output

Input = {
  "png_file": “map.png”,
  "yaml_file": "map.yaml",
  "map_name": "simple_map_1"
}
Output = {
  "error": ""
}

The full documentation exists here and here.

Author

Wojciech Dudek

Clone this wiki locally